mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
Add holonomic follower examples (#2052)
This commit is contained in:
@@ -0,0 +1,71 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "Robot.h"
|
||||
|
||||
#include <frc/smartdashboard/SmartDashboard.h>
|
||||
#include <frc2/command/CommandScheduler.h>
|
||||
|
||||
void Robot::RobotInit() {}
|
||||
|
||||
/**
|
||||
* This function is called every robot packet, no matter the mode. Use
|
||||
* this for items like diagnostics that you want to run during disabled,
|
||||
* autonomous, teleoperated and test.
|
||||
*
|
||||
* <p> This runs after the mode specific periodic functions, but before
|
||||
* LiveWindow and SmartDashboard integrated updating.
|
||||
*/
|
||||
void Robot::RobotPeriodic() { frc2::CommandScheduler::GetInstance().Run(); }
|
||||
|
||||
/**
|
||||
* This function is called once each time the robot enters Disabled mode. You
|
||||
* can use it to reset any subsystem information you want to clear when the
|
||||
* robot is disabled.
|
||||
*/
|
||||
void Robot::DisabledInit() {}
|
||||
|
||||
void Robot::DisabledPeriodic() {}
|
||||
|
||||
/**
|
||||
* This autonomous runs the autonomous command selected by your {@link
|
||||
* RobotContainer} class.
|
||||
*/
|
||||
void Robot::AutonomousInit() {
|
||||
m_autonomousCommand = m_container.GetAutonomousCommand();
|
||||
|
||||
if (m_autonomousCommand != nullptr) {
|
||||
m_autonomousCommand->Schedule();
|
||||
}
|
||||
}
|
||||
|
||||
void Robot::AutonomousPeriodic() {}
|
||||
|
||||
void Robot::TeleopInit() {
|
||||
// This makes sure that the autonomous stops running when
|
||||
// teleop starts running. If you want the autonomous to
|
||||
// continue until interrupted by another command, remove
|
||||
// this line or comment it out.
|
||||
if (m_autonomousCommand != nullptr) {
|
||||
m_autonomousCommand->Cancel();
|
||||
m_autonomousCommand = nullptr;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called periodically during operator control.
|
||||
*/
|
||||
void Robot::TeleopPeriodic() {}
|
||||
|
||||
/**
|
||||
* This function is called periodically during test mode.
|
||||
*/
|
||||
void Robot::TestPeriodic() {}
|
||||
|
||||
#ifndef RUNNING_FRC_TESTS
|
||||
int main() { return frc::StartRobot<Robot>(); }
|
||||
#endif
|
||||
@@ -0,0 +1,116 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "RobotContainer.h"
|
||||
|
||||
#include <frc/controller/PIDController.h>
|
||||
#include <frc/geometry/Translation2d.h>
|
||||
#include <frc/shuffleboard/Shuffleboard.h>
|
||||
#include <frc/trajectory/Trajectory.h>
|
||||
#include <frc/trajectory/TrajectoryGenerator.h>
|
||||
#include <frc/trajectory/constraint/MecanumDriveKinematicsConstraint.h>
|
||||
#include <frc2/command/InstantCommand.h>
|
||||
#include <frc2/command/MecanumControllerCommand.h>
|
||||
#include <frc2/command/SequentialCommandGroup.h>
|
||||
#include <frc2/command/button/JoystickButton.h>
|
||||
|
||||
#include "Constants.h"
|
||||
|
||||
using namespace DriveConstants;
|
||||
|
||||
const frc::MecanumDriveKinematics DriveConstants::kDriveKinematics{
|
||||
frc::Translation2d(kWheelBase / 2, kTrackWidth / 2),
|
||||
frc::Translation2d(kWheelBase / 2, -kTrackWidth / 2),
|
||||
frc::Translation2d(-kWheelBase / 2, kTrackWidth / 2),
|
||||
frc::Translation2d(-kWheelBase / 2, -kTrackWidth / 2)};
|
||||
|
||||
RobotContainer::RobotContainer() {
|
||||
// Initialize all of your commands and subsystems here
|
||||
|
||||
// Configure the button bindings
|
||||
ConfigureButtonBindings();
|
||||
|
||||
// Set up default drive command
|
||||
m_drive.SetDefaultCommand(frc2::RunCommand(
|
||||
[this] {
|
||||
m_drive.Drive(m_driverController.GetY(frc::GenericHID::kLeftHand),
|
||||
m_driverController.GetX(frc::GenericHID::kRightHand),
|
||||
m_driverController.GetX(frc::GenericHID::kLeftHand),
|
||||
false);
|
||||
},
|
||||
{&m_drive}));
|
||||
}
|
||||
|
||||
void RobotContainer::ConfigureButtonBindings() {
|
||||
// Configure your button bindings here
|
||||
|
||||
// While holding the shoulder button, drive at half speed
|
||||
frc2::JoystickButton(&m_driverController, 6)
|
||||
.WhenPressed(&m_driveHalfSpeed)
|
||||
.WhenReleased(&m_driveFullSpeed);
|
||||
}
|
||||
|
||||
frc2::Command* RobotContainer::GetAutonomousCommand() {
|
||||
// Set up config for trajectory
|
||||
frc::TrajectoryConfig config(AutoConstants::kMaxSpeed,
|
||||
AutoConstants::kMaxAcceleration);
|
||||
// Add kinematics to ensure max speed is actually obeyed
|
||||
config.SetKinematics(DriveConstants::kDriveKinematics);
|
||||
|
||||
// An example trajectory to follow. All units in meters.
|
||||
auto exampleTrajectory = frc::TrajectoryGenerator::GenerateTrajectory(
|
||||
// Start at the origin facing the +X direction
|
||||
frc::Pose2d(0_m, 0_m, frc::Rotation2d(0_deg)),
|
||||
// Pass through these two interior waypoints, making an 's' curve path
|
||||
{frc::Translation2d(1_m, 1_m), frc::Translation2d(2_m, -1_m)},
|
||||
// End 3 meters straight ahead of where we started, facing forward
|
||||
frc::Pose2d(3_m, 0_m, frc::Rotation2d(0_deg)),
|
||||
// Pass the config
|
||||
config);
|
||||
|
||||
frc2::MecanumControllerCommand mecanumControllerCommand(
|
||||
exampleTrajectory, [this]() { return m_drive.GetPose(); },
|
||||
|
||||
frc::SimpleMotorFeedforward<units::meters>(ks, kv, ka),
|
||||
DriveConstants::kDriveKinematics,
|
||||
|
||||
frc2::PIDController(AutoConstants::kPXController, 0, 0),
|
||||
frc2::PIDController(AutoConstants::kPYController, 0, 0),
|
||||
frc::ProfiledPIDController<units::radians>(
|
||||
AutoConstants::kPThetaController, 0, 0,
|
||||
AutoConstants::kThetaControllerConstraints),
|
||||
|
||||
AutoConstants::kMaxSpeed,
|
||||
|
||||
[this]() {
|
||||
return frc::MecanumDriveWheelSpeeds{
|
||||
units::meters_per_second_t(m_drive.GetFrontLeftEncoder().GetRate()),
|
||||
units::meters_per_second_t(
|
||||
m_drive.GetFrontRightEncoder().GetRate()),
|
||||
units::meters_per_second_t(m_drive.GetRearLeftEncoder().GetRate()),
|
||||
units::meters_per_second_t(
|
||||
m_drive.GetRearRightEncoder().GetRate())};
|
||||
},
|
||||
|
||||
frc2::PIDController(DriveConstants::kPFrontLeftVel, 0, 0),
|
||||
frc2::PIDController(DriveConstants::kPRearLeftVel, 0, 0),
|
||||
frc2::PIDController(DriveConstants::kPFrontRightVel, 0, 0),
|
||||
frc2::PIDController(DriveConstants::kPRearRightVel, 0, 0),
|
||||
|
||||
[this](units::volt_t frontLeft, units::volt_t rearLeft,
|
||||
units::volt_t frontRight, units::volt_t rearRight) {
|
||||
m_drive.SetSpeedControllersVolts(frontLeft, rearLeft, frontRight,
|
||||
rearRight);
|
||||
},
|
||||
|
||||
{&m_drive});
|
||||
|
||||
// no auto
|
||||
return new frc2::SequentialCommandGroup(
|
||||
std::move(mecanumControllerCommand),
|
||||
frc2::InstantCommand([this]() { m_drive.Drive(0, 0, 0, false); }, {}));
|
||||
}
|
||||
@@ -0,0 +1,121 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "subsystems/DriveSubsystem.h"
|
||||
|
||||
#include <frc/geometry/Rotation2d.h>
|
||||
#include <units/units.h>
|
||||
|
||||
#include "Constants.h"
|
||||
|
||||
using namespace DriveConstants;
|
||||
|
||||
DriveSubsystem::DriveSubsystem()
|
||||
: m_frontLeft{kFrontLeftMotorPort},
|
||||
m_rearLeft{kRearLeftMotorPort},
|
||||
m_frontRight{kFrontRightMotorPort},
|
||||
m_rearRight{kRearRightMotorPort},
|
||||
|
||||
m_frontLeftEncoder{kFrontLeftEncoderPorts[0], kFrontLeftEncoderPorts[1],
|
||||
kFrontLeftEncoderReversed},
|
||||
m_rearLeftEncoder{kRearLeftEncoderPorts[0], kRearLeftEncoderPorts[1],
|
||||
kRearLeftEncoderReversed},
|
||||
m_frontRightEncoder{kFrontRightEncoderPorts[0],
|
||||
kFrontRightEncoderPorts[1],
|
||||
kFrontRightEncoderReversed},
|
||||
m_rearRightEncoder{kRearRightEncoderPorts[0], kRearRightEncoderPorts[1],
|
||||
kRearRightEncoderReversed},
|
||||
|
||||
m_odometry{kDriveKinematics,
|
||||
frc::Rotation2d(units::degree_t(GetHeading())),
|
||||
frc::Pose2d()} {
|
||||
// Set the distance per pulse for the encoders
|
||||
m_frontLeftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
|
||||
m_rearLeftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
|
||||
m_frontRightEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
|
||||
m_rearRightEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
|
||||
}
|
||||
|
||||
void DriveSubsystem::Periodic() {
|
||||
// Implementation of subsystem periodic method goes here.
|
||||
m_odometry.Update(
|
||||
frc::Rotation2d(units::degree_t(GetHeading())),
|
||||
frc::MecanumDriveWheelSpeeds{
|
||||
units::meters_per_second_t(m_frontLeftEncoder.GetRate()),
|
||||
units::meters_per_second_t(m_rearLeftEncoder.GetRate()),
|
||||
units::meters_per_second_t(m_frontRightEncoder.GetRate()),
|
||||
units::meters_per_second_t(m_rearRightEncoder.GetRate())});
|
||||
}
|
||||
|
||||
void DriveSubsystem::Drive(double xSpeed, double ySpeed, double rot,
|
||||
bool feildRelative) {
|
||||
if (feildRelative) {
|
||||
m_drive.DriveCartesian(ySpeed, xSpeed, rot, -m_gyro.GetAngle());
|
||||
} else {
|
||||
m_drive.DriveCartesian(ySpeed, xSpeed, rot);
|
||||
}
|
||||
}
|
||||
|
||||
void DriveSubsystem::SetSpeedControllersVolts(units::volt_t frontLeftPower,
|
||||
units::volt_t rearLeftPower,
|
||||
units::volt_t frontRightPower,
|
||||
units::volt_t rearRightPower) {
|
||||
m_frontLeft.SetVoltage(frontLeftPower);
|
||||
m_rearLeft.SetVoltage(rearLeftPower);
|
||||
m_frontRight.SetVoltage(frontRightPower);
|
||||
m_rearRight.SetVoltage(rearRightPower);
|
||||
}
|
||||
|
||||
void DriveSubsystem::ResetEncoders() {
|
||||
m_frontLeftEncoder.Reset();
|
||||
m_rearLeftEncoder.Reset();
|
||||
m_frontRightEncoder.Reset();
|
||||
m_rearRightEncoder.Reset();
|
||||
}
|
||||
|
||||
frc::Encoder& DriveSubsystem::GetFrontLeftEncoder() {
|
||||
return m_frontLeftEncoder;
|
||||
}
|
||||
|
||||
frc::Encoder& DriveSubsystem::GetRearLeftEncoder() { return m_rearLeftEncoder; }
|
||||
|
||||
frc::Encoder& DriveSubsystem::GetFrontRightEncoder() {
|
||||
return m_frontRightEncoder;
|
||||
}
|
||||
|
||||
frc::Encoder& DriveSubsystem::GetRearRightEncoder() {
|
||||
return m_rearRightEncoder;
|
||||
}
|
||||
|
||||
frc::MecanumDriveWheelSpeeds DriveSubsystem::getCurrentWheelSpeeds() {
|
||||
return (frc::MecanumDriveWheelSpeeds{
|
||||
units::meters_per_second_t(m_frontLeftEncoder.GetRate()),
|
||||
units::meters_per_second_t(m_rearLeftEncoder.GetRate()),
|
||||
units::meters_per_second_t(m_frontRightEncoder.GetRate()),
|
||||
units::meters_per_second_t(m_rearRightEncoder.GetRate())});
|
||||
}
|
||||
|
||||
void DriveSubsystem::SetMaxOutput(double maxOutput) {
|
||||
m_drive.SetMaxOutput(maxOutput);
|
||||
}
|
||||
|
||||
double DriveSubsystem::GetHeading() {
|
||||
return std::remainder(m_gyro.GetAngle(), 360) * (kGyroReversed ? -1. : 1.);
|
||||
}
|
||||
|
||||
void DriveSubsystem::ZeroHeading() { m_gyro.Reset(); }
|
||||
|
||||
double DriveSubsystem::GetTurnRate() {
|
||||
return m_gyro.GetRate() * (kGyroReversed ? -1. : 1.);
|
||||
}
|
||||
|
||||
frc::Pose2d DriveSubsystem::GetPose() { return m_odometry.GetPose(); }
|
||||
|
||||
void DriveSubsystem::ResetOdometry(frc::Pose2d pose) {
|
||||
m_odometry.ResetPosition(pose,
|
||||
frc::Rotation2d(units::degree_t(GetHeading())));
|
||||
}
|
||||
@@ -0,0 +1,93 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include <frc/geometry/Translation2d.h>
|
||||
#include <frc/kinematics/MecanumDriveKinematics.h>
|
||||
#include <frc/trajectory/TrapezoidProfile.h>
|
||||
#include <units/units.h>
|
||||
#include <wpi/math>
|
||||
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* The Constants header provides a convenient place for teams to hold robot-wide
|
||||
* numerical or bool constants. This should not be used for any other purpose.
|
||||
*
|
||||
* It is generally a good idea to place constants into subsystem- or
|
||||
* command-specific namespaces within this header, which can then be used where
|
||||
* they are needed.
|
||||
*/
|
||||
|
||||
namespace DriveConstants {
|
||||
constexpr int kFrontLeftMotorPort = 0;
|
||||
constexpr int kRearLeftMotorPort = 1;
|
||||
constexpr int kFrontRightMotorPort = 2;
|
||||
constexpr int kRearRightMotorPort = 3;
|
||||
|
||||
constexpr int kFrontLeftEncoderPorts[]{0, 1};
|
||||
constexpr int kRearLeftEncoderPorts[]{2, 3};
|
||||
constexpr int kFrontRightEncoderPorts[]{4, 5};
|
||||
constexpr int kRearRightEncoderPorts[]{5, 6};
|
||||
|
||||
constexpr bool kFrontLeftEncoderReversed = false;
|
||||
constexpr bool kRearLeftEncoderReversed = true;
|
||||
constexpr bool kFrontRightEncoderReversed = false;
|
||||
constexpr bool kRearRightEncoderReversed = true;
|
||||
|
||||
constexpr auto kTrackWidth =
|
||||
0.5_m; // Distance between centers of right and left wheels on robot
|
||||
constexpr auto kWheelBase =
|
||||
0.7_m; // Distance between centers of front and back wheels on robot
|
||||
extern const frc::MecanumDriveKinematics kDriveKinematics;
|
||||
|
||||
constexpr int kEncoderCPR = 1024;
|
||||
constexpr double kWheelDiameterMeters = .15;
|
||||
constexpr double kEncoderDistancePerPulse =
|
||||
// Assumes the encoders are directly mounted on the wheel shafts
|
||||
(kWheelDiameterMeters * wpi::math::pi) / static_cast<double>(kEncoderCPR);
|
||||
|
||||
constexpr bool kGyroReversed = false;
|
||||
|
||||
// These are example values only - DO NOT USE THESE FOR YOUR OWN ROBOT!
|
||||
// These characterization values MUST be determined either experimentally or
|
||||
// theoretically for *your* robot's drive. The RobotPy Characterization
|
||||
// Toolsuite provides a convenient tool for obtaining these values for your
|
||||
// robot.
|
||||
constexpr auto ks = 1_V;
|
||||
constexpr auto kv = 0.8 * 1_V * 1_s / 1_m;
|
||||
constexpr auto ka = 0.15 * 1_V * 1_s * 1_s / 1_m;
|
||||
|
||||
// Example value only - as above, this must be tuned for your drive!
|
||||
constexpr double kPFrontLeftVel = 0.5;
|
||||
constexpr double kPRearLeftVel = 0.5;
|
||||
constexpr double kPFrontRightVel = 0.5;
|
||||
constexpr double kPRearRightVel = 0.5;
|
||||
} // namespace DriveConstants
|
||||
|
||||
namespace AutoConstants {
|
||||
using radians_per_second_squared_t =
|
||||
units::compound_unit<units::radians,
|
||||
units::inverse<units::squared<units::second>>>;
|
||||
|
||||
constexpr auto kMaxSpeed = units::meters_per_second_t(3);
|
||||
constexpr auto kMaxAcceleration = units::meters_per_second_squared_t(3);
|
||||
constexpr auto kMaxAngularSpeed = units::radians_per_second_t(3);
|
||||
constexpr auto kMaxAngularAcceleration =
|
||||
units::unit_t<radians_per_second_squared_t>(3);
|
||||
|
||||
constexpr double kPXController = 0.5;
|
||||
constexpr double kPYController = 0.5;
|
||||
constexpr double kPThetaController = 0.5;
|
||||
|
||||
constexpr frc::TrapezoidProfile<units::radians>::Constraints
|
||||
kThetaControllerConstraints{kMaxAngularSpeed, kMaxAngularAcceleration};
|
||||
|
||||
} // namespace AutoConstants
|
||||
|
||||
namespace OIConstants {
|
||||
constexpr int kDriverControllerPort = 1;
|
||||
} // namespace OIConstants
|
||||
@@ -0,0 +1,33 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <frc2/command/Command.h>
|
||||
|
||||
#include "RobotContainer.h"
|
||||
|
||||
class Robot : public frc::TimedRobot {
|
||||
public:
|
||||
void RobotInit() override;
|
||||
void RobotPeriodic() override;
|
||||
void DisabledInit() override;
|
||||
void DisabledPeriodic() override;
|
||||
void AutonomousInit() override;
|
||||
void AutonomousPeriodic() override;
|
||||
void TeleopInit() override;
|
||||
void TeleopPeriodic() override;
|
||||
void TestPeriodic() override;
|
||||
|
||||
private:
|
||||
// Have it null by default so that if testing teleop it
|
||||
// doesn't have undefined behavior and potentially crash.
|
||||
frc2::Command* m_autonomousCommand = nullptr;
|
||||
|
||||
RobotContainer m_container;
|
||||
};
|
||||
@@ -0,0 +1,54 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/XboxController.h>
|
||||
#include <frc/controller/PIDController.h>
|
||||
#include <frc/controller/ProfiledPIDController.h>
|
||||
#include <frc/smartdashboard/SendableChooser.h>
|
||||
#include <frc2/command/Command.h>
|
||||
#include <frc2/command/InstantCommand.h>
|
||||
#include <frc2/command/PIDCommand.h>
|
||||
#include <frc2/command/ParallelRaceGroup.h>
|
||||
#include <frc2/command/RunCommand.h>
|
||||
|
||||
#include "Constants.h"
|
||||
#include "subsystems/DriveSubsystem.h"
|
||||
|
||||
/**
|
||||
* This class is where the bulk of the robot should be declared. Since
|
||||
* Command-based is a "declarative" paradigm, very little robot logic should
|
||||
* actually be handled in the {@link Robot} periodic methods (other than the
|
||||
* scheduler calls). Instead, the structure of the robot (including subsystems,
|
||||
* commands, and button mappings) should be declared here.
|
||||
*/
|
||||
class RobotContainer {
|
||||
public:
|
||||
RobotContainer();
|
||||
|
||||
frc2::Command* GetAutonomousCommand();
|
||||
|
||||
private:
|
||||
// The driver's controller
|
||||
frc::XboxController m_driverController{OIConstants::kDriverControllerPort};
|
||||
|
||||
// The robot's subsystems and commands are defined here...
|
||||
|
||||
// The robot's subsystems
|
||||
DriveSubsystem m_drive;
|
||||
|
||||
frc2::InstantCommand m_driveHalfSpeed{[this] { m_drive.SetMaxOutput(.5); },
|
||||
{}};
|
||||
frc2::InstantCommand m_driveFullSpeed{[this] { m_drive.SetMaxOutput(1); },
|
||||
{}};
|
||||
|
||||
// The chooser for the autonomous routines
|
||||
frc::SendableChooser<frc2::Command*> m_chooser;
|
||||
|
||||
void ConfigureButtonBindings();
|
||||
};
|
||||
@@ -0,0 +1,166 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc/ADXRS450_Gyro.h>
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/PWMVictorSPX.h>
|
||||
#include <frc/drive/MecanumDrive.h>
|
||||
#include <frc/geometry/Pose2d.h>
|
||||
#include <frc/geometry/Rotation2d.h>
|
||||
#include <frc/interfaces/Gyro.h>
|
||||
#include <frc/kinematics/MecanumDriveOdometry.h>
|
||||
#include <frc/kinematics/MecanumDriveWheelSpeeds.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
|
||||
#include "Constants.h"
|
||||
|
||||
class DriveSubsystem : public frc2::SubsystemBase {
|
||||
public:
|
||||
DriveSubsystem();
|
||||
|
||||
/**
|
||||
* Will be called periodically whenever the CommandScheduler runs.
|
||||
*/
|
||||
void Periodic() override;
|
||||
|
||||
// Subsystem methods go here.
|
||||
|
||||
/**
|
||||
* Drives the robot at given x, y and theta speeds. Speeds range from [-1, 1]
|
||||
* and the linear speeds have no effect on the angular speed.
|
||||
*
|
||||
* @param xSpeed Speed of the robot in the x direction
|
||||
* (forward/backwards).
|
||||
* @param ySpeed Speed of the robot in the y direction (sideways).
|
||||
* @param rot Angular rate of the robot.
|
||||
* @param fieldRelative Whether the provided x and y speeds are relative to
|
||||
* the field.
|
||||
*/
|
||||
void Drive(double xSpeed, double ySpeed, double rot, bool feildRelative);
|
||||
|
||||
/**
|
||||
* Resets the drive encoders to currently read a position of 0.
|
||||
*/
|
||||
void ResetEncoders();
|
||||
|
||||
/**
|
||||
* Gets the front left drive encoder.
|
||||
*
|
||||
* @return the front left drive encoder
|
||||
*/
|
||||
frc::Encoder& GetFrontLeftEncoder();
|
||||
|
||||
/**
|
||||
* Gets the rear left drive encoder.
|
||||
*
|
||||
* @return the rear left drive encoder
|
||||
*/
|
||||
frc::Encoder& GetRearLeftEncoder();
|
||||
|
||||
/**
|
||||
* Gets the front right drive encoder.
|
||||
*
|
||||
* @return the front right drive encoder
|
||||
*/
|
||||
frc::Encoder& GetFrontRightEncoder();
|
||||
|
||||
/**
|
||||
* Gets the rear right drive encoder.
|
||||
*
|
||||
* @return the rear right drive encoder
|
||||
*/
|
||||
frc::Encoder& GetRearRightEncoder();
|
||||
|
||||
/**
|
||||
* Gets the wheel speeds.
|
||||
*
|
||||
* @return the current wheel speeds.
|
||||
*/
|
||||
frc::MecanumDriveWheelSpeeds getCurrentWheelSpeeds();
|
||||
|
||||
/**
|
||||
* Sets the drive SpeedControllers to a desired voltage.
|
||||
*/
|
||||
void SetSpeedControllersVolts(units::volt_t frontLeftPower,
|
||||
units::volt_t rearLeftPower,
|
||||
units::volt_t frontRightPower,
|
||||
units::volt_t rearRightPower);
|
||||
|
||||
/**
|
||||
* Sets the max output of the drive. Useful for scaling the drive to drive
|
||||
* more slowly.
|
||||
*
|
||||
* @param maxOutput the maximum output to which the drive will be constrained
|
||||
*/
|
||||
void SetMaxOutput(double maxOutput);
|
||||
|
||||
/**
|
||||
* Returns the heading of the robot.
|
||||
*
|
||||
* @return the robot's heading in degrees, from 180 to 180
|
||||
*/
|
||||
double GetHeading();
|
||||
|
||||
/**
|
||||
* Zeroes the heading of the robot.
|
||||
*/
|
||||
void ZeroHeading();
|
||||
|
||||
/**
|
||||
* Returns the turn rate of the robot.
|
||||
*
|
||||
* @return The turn rate of the robot, in degrees per second
|
||||
*/
|
||||
double GetTurnRate();
|
||||
|
||||
/**
|
||||
* Returns the currently-estimated pose of the robot.
|
||||
*
|
||||
* @return The pose.
|
||||
*/
|
||||
frc::Pose2d GetPose();
|
||||
|
||||
/**
|
||||
* Resets the odometry to the specified pose.
|
||||
*
|
||||
* @param pose The pose to which to set the odometry.
|
||||
*/
|
||||
void ResetOdometry(frc::Pose2d pose);
|
||||
|
||||
private:
|
||||
// Components (e.g. motor controllers and sensors) should generally be
|
||||
// declared private and exposed only through public methods.
|
||||
|
||||
// The motor controllers
|
||||
frc::PWMVictorSPX m_frontLeft;
|
||||
frc::PWMVictorSPX m_rearLeft;
|
||||
frc::PWMVictorSPX m_frontRight;
|
||||
frc::PWMVictorSPX m_rearRight;
|
||||
|
||||
// The robot's drive
|
||||
frc::MecanumDrive m_drive{m_frontLeft, m_rearLeft, m_frontRight, m_rearRight};
|
||||
|
||||
// The front-left-side drive encoder
|
||||
frc::Encoder m_frontLeftEncoder;
|
||||
|
||||
// The rear-left-side drive encoder
|
||||
frc::Encoder m_rearLeftEncoder;
|
||||
|
||||
// The front-right--side drive encoder
|
||||
frc::Encoder m_frontRightEncoder;
|
||||
|
||||
// The rear-right-side drive encoder
|
||||
frc::Encoder m_rearRightEncoder;
|
||||
|
||||
// The gyro sensor
|
||||
frc::ADXRS450_Gyro m_gyro;
|
||||
|
||||
// Odometry class for tracking robot pose
|
||||
frc::MecanumDriveOdometry m_odometry;
|
||||
};
|
||||
Reference in New Issue
Block a user