Add TrapezoidProfile external PID examples (#2131)

This commit is contained in:
Oblarg
2019-12-07 16:37:54 -05:00
committed by Peter Johnson
parent 5c6b8a0f45
commit ccdd0fbdb2
54 changed files with 2734 additions and 73 deletions

View File

@@ -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

View File

@@ -0,0 +1,51 @@
/*----------------------------------------------------------------------------*/
/* 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/shuffleboard/Shuffleboard.h>
#include <frc2/command/button/JoystickButton.h>
#include <units/units.h>
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.ArcadeDrive(
m_driverController.GetY(frc::GenericHID::kLeftHand),
m_driverController.GetX(frc::GenericHID::kRightHand));
},
{&m_drive}));
}
void RobotContainer::ConfigureButtonBindings() {
// Configure your button bindings here
// Move the arm to 2 radians above horizontal when the 'A' button is pressed.
frc2::JoystickButton(&m_driverController, 1)
.WhenPressed([this] { m_arm.SetGoal(2_rad); }, {&m_arm});
// Move the arm to neutral position when the 'B' button is pressed.
frc2::JoystickButton(&m_driverController, 1)
.WhenPressed([this] { m_arm.SetGoal(ArmConstants::kArmOffset); },
{&m_arm});
// While holding the shoulder button, drive at half speed
frc2::JoystickButton(&m_driverController, 6)
.WhenPressed([this] { m_drive.SetMaxOutput(.5); })
.WhenReleased([this] { m_drive.SetMaxOutput(1); });
}
frc2::Command* RobotContainer::GetAutonomousCommand() {
// Runs the chosen command in autonomous
return new frc2::InstantCommand([] {});
}

View File

@@ -0,0 +1,30 @@
/*----------------------------------------------------------------------------*/
/* 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/ArmSubsystem.h"
#include "Constants.h"
using namespace ArmConstants;
using State = frc::TrapezoidProfile<units::radians>::State;
ArmSubsystem::ArmSubsystem()
: frc2::TrapezoidProfileSubsystem<units::radians>(
{kMaxVelocity, kMaxAcceleration}, kArmOffset),
m_motor(kMotorPort),
m_feedforward(kS, kCos, kV, kA) {
m_motor.SetPID(kP, 0, 0);
}
void ArmSubsystem::UseState(State setpoint) {
// Calculate the feedforward from the sepoint
units::volt_t feedforward =
m_feedforward.Calculate(setpoint.position, setpoint.velocity);
// Add the feedforward to the PID output to get the motor output
m_motor.SetSetpoint(ExampleSmartMotorController::PIDMode::kPosition,
setpoint.position.to<double>(), feedforward / 12_V);
}

View File

@@ -0,0 +1,47 @@
/*----------------------------------------------------------------------------*/
/* 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"
using namespace DriveConstants;
DriveSubsystem::DriveSubsystem()
: m_left1{kLeftMotor1Port},
m_left2{kLeftMotor2Port},
m_right1{kRightMotor1Port},
m_right2{kRightMotor2Port},
m_leftEncoder{kLeftEncoderPorts[0], kLeftEncoderPorts[1]},
m_rightEncoder{kRightEncoderPorts[0], kRightEncoderPorts[1]} {
// Set the distance per pulse for the encoders
m_leftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
m_rightEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
}
void DriveSubsystem::Periodic() {
// Implementation of subsystem periodic method goes here.
}
void DriveSubsystem::ArcadeDrive(double fwd, double rot) {
m_drive.ArcadeDrive(fwd, rot);
}
void DriveSubsystem::ResetEncoders() {
m_leftEncoder.Reset();
m_rightEncoder.Reset();
}
double DriveSubsystem::GetAverageEncoderDistance() {
return (m_leftEncoder.GetDistance() + m_rightEncoder.GetDistance()) / 2.0;
}
frc::Encoder& DriveSubsystem::GetLeftEncoder() { return m_leftEncoder; }
frc::Encoder& DriveSubsystem::GetRightEncoder() { return m_rightEncoder; }
void DriveSubsystem::SetMaxOutput(double maxOutput) {
m_drive.SetMaxOutput(maxOutput);
}

View File

@@ -0,0 +1,71 @@
/*----------------------------------------------------------------------------*/
/* 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 <units/units.h>
#include <wpi/math>
/**
* 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 kLeftMotor1Port = 0;
constexpr int kLeftMotor2Port = 1;
constexpr int kRightMotor1Port = 2;
constexpr int kRightMotor2Port = 3;
constexpr int kLeftEncoderPorts[]{0, 1};
constexpr int kRightEncoderPorts[]{2, 3};
constexpr bool kLeftEncoderReversed = false;
constexpr bool kRightEncoderReversed = true;
constexpr int kEncoderCPR = 1024;
constexpr double kWheelDiameterInches = 6;
constexpr double kEncoderDistancePerPulse =
// Assumes the encoders are directly mounted on the wheel shafts
(kWheelDiameterInches * wpi::math::pi) / static_cast<double>(kEncoderCPR);
} // namespace DriveConstants
namespace ArmConstants {
constexpr int kMotorPort = 4;
constexpr double kP = 1;
// These are fake gains; in actuality these must be determined individually for
// each robot
constexpr auto kS = 1_V;
constexpr auto kCos = 1_V;
constexpr auto kV = 0.5_V * 1_s / 1_rad;
constexpr auto kA = 0.1_V * 1_s * 1_s / 1_rad;
constexpr auto kMaxVelocity = 3_rad_per_s;
constexpr auto kMaxAcceleration = 10_rad / (1_s * 1_s);
constexpr int kEncoderPorts[]{4, 5};
constexpr int kEncoderPPR = 256;
constexpr auto kEncoderDistancePerPulse = 2.0_rad * wpi::math::pi / kEncoderPPR;
// The offset of the arm from the horizontal in its neutral position,
// measured from the horizontal
constexpr auto kArmOffset = 0.5_rad;
} // namespace ArmConstants
namespace AutoConstants {
constexpr auto kAutoTimeoutSeconds = 12_s;
constexpr auto kAutoShootTimeSeconds = 7_s;
} // namespace AutoConstants
namespace OIConstants {
constexpr int kDriverControllerPort = 1;
} // namespace OIConstants

View File

@@ -0,0 +1,87 @@
/*----------------------------------------------------------------------------*/
/* 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/SpeedController.h>
/**
* A simplified stub class that simulates the API of a common "smart" motor
* controller.
*
* <p>Has no actual functionality.
*/
class ExampleSmartMotorController : public frc::SpeedController {
public:
enum PIDMode { kPosition, kVelocity, kMovementWitchcraft };
/**
* Creates a new ExampleSmartMotorController.
*
* @param port The port for the controller.
*/
explicit ExampleSmartMotorController(int port) {}
/**
* Example method for setting the PID gains of the smart controller.
*
* @param kp The proportional gain.
* @param ki The integral gain.
* @param kd The derivative gain.
*/
void SetPID(double kp, double ki, double kd) {}
/**
* Example method for setting the setpoint of the smart controller in PID
* mode.
*
* @param mode The mode of the PID controller.
* @param setpoint The controller setpoint.
* @param arbFeedforward An arbitrary feedforward output (from -1 to 1).
*/
void SetSetpoint(PIDMode mode, double setpoint, double arbFeedforward) {}
/**
* Places this motor controller in follower mode.
*
* @param master The master to follow.
*/
void Follow(ExampleSmartMotorController master) {}
/**
* Returns the encoder distance.
*
* @return The current encoder distance.
*/
double GetEncoderDistance() { return 0; }
/**
* Returns the encoder rate.
*
* @return The current encoder rate.
*/
double GetEncoderRate() { return 0; }
/**
* Resets the encoder to zero distance.
*/
void ResetEncoder() {}
void Set(double speed) override {}
double Get() const override { return 0; }
void SetInverted(bool isInverted) override {}
bool GetInverted() const override { return false; }
void Disable() override {}
void StopMotor() override {}
void PIDWrite(double output) override {}
};

View File

@@ -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;
};

View File

@@ -0,0 +1,53 @@
/*----------------------------------------------------------------------------*/
/* 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/smartdashboard/SendableChooser.h>
#include <frc2/command/Command.h>
#include <frc2/command/ConditionalCommand.h>
#include <frc2/command/InstantCommand.h>
#include <frc2/command/ParallelRaceGroup.h>
#include <frc2/command/RunCommand.h>
#include <frc2/command/SequentialCommandGroup.h>
#include <frc2/command/WaitCommand.h>
#include <frc2/command/WaitUntilCommand.h>
#include "Constants.h"
#include "subsystems/ArmSubsystem.h"
#include "subsystems/DriveSubsystem.h"
namespace ac = AutoConstants;
/**
* 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;
ArmSubsystem m_arm;
// The chooser for the autonomous routines
void ConfigureButtonBindings();
};

View File

@@ -0,0 +1,30 @@
/*----------------------------------------------------------------------------*/
/* 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/controller/ArmFeedforward.h>
#include <frc2/command/TrapezoidProfileSubsystem.h>
#include <units/units.h>
#include "ExampleSmartMotorController.h"
/**
* A robot arm subsystem that moves with a motion profile.
*/
class ArmSubsystem : public frc2::TrapezoidProfileSubsystem<units::radians> {
using State = frc::TrapezoidProfile<units::radians>::State;
public:
ArmSubsystem();
void UseState(State setpoint) override;
private:
ExampleSmartMotorController m_motor;
frc::ArmFeedforward m_feedforward;
};

View File

@@ -0,0 +1,95 @@
/*----------------------------------------------------------------------------*/
/* 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/Encoder.h>
#include <frc/PWMVictorSPX.h>
#include <frc/SpeedControllerGroup.h>
#include <frc/drive/DifferentialDrive.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 using arcade controls.
*
* @param fwd the commanded forward movement
* @param rot the commanded rotation
*/
void ArcadeDrive(double fwd, double rot);
/**
* Resets the drive encoders to currently read a position of 0.
*/
void ResetEncoders();
/**
* Gets the average distance of the TWO encoders.
*
* @return the average of the TWO encoder readings
*/
double GetAverageEncoderDistance();
/**
* Gets the left drive encoder.
*
* @return the left drive encoder
*/
frc::Encoder& GetLeftEncoder();
/**
* Gets the right drive encoder.
*
* @return the right drive encoder
*/
frc::Encoder& GetRightEncoder();
/**
* 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);
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_left1;
frc::PWMVictorSPX m_left2;
frc::PWMVictorSPX m_right1;
frc::PWMVictorSPX m_right2;
// The motors on the left side of the drive
frc::SpeedControllerGroup m_leftMotors{m_left1, m_left2};
// The motors on the right side of the drive
frc::SpeedControllerGroup m_rightMotors{m_right1, m_right2};
// The robot's drive
frc::DifferentialDrive m_drive{m_leftMotors, m_rightMotors};
// The left-side drive encoder
frc::Encoder m_leftEncoder;
// The right-side drive encoder
frc::Encoder m_rightEncoder;
};

View File

@@ -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

View File

@@ -0,0 +1,67 @@
/*----------------------------------------------------------------------------*/
/* 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/shuffleboard/Shuffleboard.h>
#include <frc2/command/button/JoystickButton.h>
#include "commands/DriveDistanceProfiled.h"
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.ArcadeDrive(
m_driverController.GetY(frc::GenericHID::kLeftHand),
m_driverController.GetX(frc::GenericHID::kRightHand));
},
{&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);
// Drive forward by 3 meters when the 'A' button is pressed, with a timeout of
// 10 seconds
frc2::JoystickButton(&m_driverController, 1)
.WhenPressed(DriveDistanceProfiled(3_m, &m_drive).WithTimeout(10_s));
// Do the same thing as above when the 'B' button is pressed, but defined
// inline
frc2::JoystickButton(&m_driverController, 2)
.WhenPressed(
frc2::TrapezoidProfileCommand<units::meters>(
frc::TrapezoidProfile<units::meters>(
// Limit the max acceleration and velocity
{DriveConstants::kMaxSpeed, DriveConstants::kMaxAcceleration},
// End at desired position in meters; implicitly starts at 0
{3_m, 0_mps}),
// Pipe the profile state to the drive
[this](auto setpointState) {
m_drive.SetDriveStates(setpointState, setpointState);
},
// Require the drive
{&m_drive})
.BeforeStarting([this]() { m_drive.ResetEncoders(); })
.WithTimeout(10_s));
}
frc2::Command* RobotContainer::GetAutonomousCommand() {
// Runs the chosen command in autonomous
return new frc2::InstantCommand([] {});
}

View File

@@ -0,0 +1,30 @@
/*----------------------------------------------------------------------------*/
/* 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 "commands/DriveDistanceProfiled.h"
#include "Constants.h"
using namespace DriveConstants;
DriveDistanceProfiled::DriveDistanceProfiled(units::meter_t distance,
DriveSubsystem* drive)
: CommandHelper(
frc::TrapezoidProfile<units::meters>(
// Limit the max acceleration and velocity
{kMaxSpeed, kMaxAcceleration},
// End at desired position in meters; implicitly starts at 0
{distance, 0_mps}),
// Pipe the profile state to the drive
[drive](auto setpointState) {
drive->SetDriveStates(setpointState, setpointState);
},
// Require the drive
{drive}) {
// Reset drive encoders since we're starting at 0
drive->ResetEncoders();
}

View File

@@ -0,0 +1,59 @@
/*----------------------------------------------------------------------------*/
/* 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"
using namespace DriveConstants;
DriveSubsystem::DriveSubsystem()
: m_leftMaster{kLeftMotor1Port},
m_leftSlave{kLeftMotor2Port},
m_rightMaster{kRightMotor1Port},
m_rightSlave{kRightMotor2Port},
m_feedforward{ks, kv, ka} {
m_leftSlave.Follow(m_leftMaster);
m_rightSlave.Follow(m_rightMaster);
m_leftMaster.SetPID(kp, 0, 0);
m_rightMaster.SetPID(kp, 0, 0);
}
void DriveSubsystem::Periodic() {
// Implementation of subsystem periodic method goes here.
}
void DriveSubsystem::SetDriveStates(
frc::TrapezoidProfile<units::meters>::State left,
frc::TrapezoidProfile<units::meters>::State right) {
m_leftMaster.SetSetpoint(ExampleSmartMotorController::PIDMode::kPosition,
left.position.to<double>(),
m_feedforward.Calculate(left.velocity) / 12_V);
m_rightMaster.SetSetpoint(ExampleSmartMotorController::PIDMode::kPosition,
right.position.to<double>(),
m_feedforward.Calculate(right.velocity) / 12_V);
}
void DriveSubsystem::ArcadeDrive(double fwd, double rot) {
m_drive.ArcadeDrive(fwd, rot);
}
void DriveSubsystem::ResetEncoders() {
m_leftMaster.ResetEncoder();
m_rightMaster.ResetEncoder();
}
units::meter_t DriveSubsystem::GetLeftEncoderDistance() {
return units::meter_t(m_leftMaster.GetEncoderDistance());
}
units::meter_t DriveSubsystem::GetRightEncoderDistance() {
return units::meter_t(m_rightMaster.GetEncoderDistance());
}
void DriveSubsystem::SetMaxOutput(double maxOutput) {
m_drive.SetMaxOutput(maxOutput);
}

View File

@@ -0,0 +1,46 @@
/*----------------------------------------------------------------------------*/
/* 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 <units/units.h>
#include <wpi/math>
/**
* 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 kLeftMotor1Port = 0;
constexpr int kLeftMotor2Port = 1;
constexpr int kRightMotor1Port = 2;
constexpr int kRightMotor2Port = 3;
// 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_V * 1_s / 1_m;
constexpr auto ka = 0.15_V * 1_s * 1_s / 1_m;
constexpr double kp = 1;
constexpr auto kMaxSpeed = 3_mps;
constexpr auto kMaxAcceleration = 3_mps_sq;
} // namespace DriveConstants
namespace OIConstants {
constexpr int kDriverControllerPort = 1;
} // namespace OIConstants

View File

@@ -0,0 +1,87 @@
/*----------------------------------------------------------------------------*/
/* 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/SpeedController.h>
/**
* A simplified stub class that simulates the API of a common "smart" motor
* controller.
*
* <p>Has no actual functionality.
*/
class ExampleSmartMotorController : public frc::SpeedController {
public:
enum PIDMode { kPosition, kVelocity, kMovementWitchcraft };
/**
* Creates a new ExampleSmartMotorController.
*
* @param port The port for the controller.
*/
explicit ExampleSmartMotorController(int port) {}
/**
* Example method for setting the PID gains of the smart controller.
*
* @param kp The proportional gain.
* @param ki The integral gain.
* @param kd The derivative gain.
*/
void SetPID(double kp, double ki, double kd) {}
/**
* Example method for setting the setpoint of the smart controller in PID
* mode.
*
* @param mode The mode of the PID controller.
* @param setpoint The controller setpoint.
* @param arbFeedforward An arbitrary feedforward output (from -1 to 1).
*/
void SetSetpoint(PIDMode mode, double setpoint, double arbFeedforward) {}
/**
* Places this motor controller in follower mode.
*
* @param master The master to follow.
*/
void Follow(ExampleSmartMotorController master) {}
/**
* Returns the encoder distance.
*
* @return The current encoder distance.
*/
double GetEncoderDistance() { return 0; }
/**
* Returns the encoder rate.
*
* @return The current encoder rate.
*/
double GetEncoderRate() { return 0; }
/**
* Resets the encoder to zero distance.
*/
void ResetEncoder() {}
void Set(double speed) override {}
double Get() const override { return 0; }
void SetInverted(bool isInverted) override {}
bool GetInverted() const override { return false; }
void Disable() override {}
void StopMotor() override {}
void PIDWrite(double output) override {}
};

View File

@@ -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;
};

View File

@@ -0,0 +1,50 @@
/*----------------------------------------------------------------------------*/
/* 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/smartdashboard/SendableChooser.h>
#include <frc2/command/Command.h>
#include <frc2/command/InstantCommand.h>
#include <frc2/command/ParallelRaceGroup.h>
#include <frc2/command/RunCommand.h>
#include <frc2/command/SequentialCommandGroup.h>
#include <frc2/command/StartEndCommand.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(0.5); },
{}};
frc2::InstantCommand m_driveFullSpeed{[this] { m_drive.SetMaxOutput(1); },
{}};
void ConfigureButtonBindings();
};

View File

@@ -0,0 +1,20 @@
/*----------------------------------------------------------------------------*/
/* 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 <frc2/command/CommandHelper.h>
#include <frc2/command/TrapezoidProfileCommand.h>
#include "subsystems/DriveSubsystem.h"
class DriveDistanceProfiled
: public frc2::CommandHelper<frc2::TrapezoidProfileCommand<units::meters>,
DriveDistanceProfiled> {
public:
DriveDistanceProfiled(units::meter_t distance, DriveSubsystem* drive);
};

View File

@@ -0,0 +1,90 @@
/*----------------------------------------------------------------------------*/
/* 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/Encoder.h>
#include <frc/controller/SimpleMotorFeedforward.h>
#include <frc/drive/DifferentialDrive.h>
#include <frc/trajectory/TrapezoidProfile.h>
#include <frc2/command/SubsystemBase.h>
#include <units/units.h>
#include "Constants.h"
#include "ExampleSmartMotorController.h"
class DriveSubsystem : public frc2::SubsystemBase {
public:
DriveSubsystem();
/**
* Will be called periodically whenever the CommandScheduler runs.
*/
void Periodic() override;
// Subsystem methods go here.
/**
* Attempts to follow the given drive states using offboard PID.
*
* @param left The left wheel state.
* @param right The right wheel state.
*/
void SetDriveStates(frc::TrapezoidProfile<units::meters>::State left,
frc::TrapezoidProfile<units::meters>::State right);
/**
* Drives the robot using arcade controls.
*
* @param fwd the commanded forward movement
* @param rot the commanded rotation
*/
void ArcadeDrive(double fwd, double rot);
/**
* Resets the drive encoders to currently read a position of 0.
*/
void ResetEncoders();
/**
* Gets the distance of the left encoder.
*
* @return the average of the TWO encoder readings
*/
units::meter_t GetLeftEncoderDistance();
/**
* Gets the distance of the right encoder.
*
* @return the average of the TWO encoder readings
*/
units::meter_t GetRightEncoderDistance();
/**
* 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);
private:
// Components (e.g. motor controllers and sensors) should generally be
// declared private and exposed only through public methods.
// The motor controllers
ExampleSmartMotorController m_leftMaster;
ExampleSmartMotorController m_leftSlave;
ExampleSmartMotorController m_rightMaster;
ExampleSmartMotorController m_rightSlave;
// A feedforward component for the drive
frc::SimpleMotorFeedforward<units::meters> m_feedforward;
// The robot's drive
frc::DifferentialDrive m_drive{m_leftMaster, m_rightMaster};
};

View File

@@ -5,20 +5,22 @@
/* the project. */
/*----------------------------------------------------------------------------*/
#include <frc/Encoder.h>
#include <frc/Joystick.h>
#include <frc/PWMVictorSPX.h>
#include <frc/TimedRobot.h>
#include <frc/controller/PIDController.h>
#include <frc/controller/SimpleMotorFeedforward.h>
#include <frc/trajectory/TrapezoidProfile.h>
#include <units/units.h>
#include <wpi/math>
#include "ExampleSmartMotorController.h"
class Robot : public frc::TimedRobot {
public:
static constexpr units::second_t kDt = 20_ms;
Robot() {
m_encoder.SetDistancePerPulse(1.0 / 360.0 * 2.0 * wpi::math::pi * 1.5);
// Note: These gains are fake, and will have to be tuned for your robot.
m_motor.SetPID(1.3, 0.0, 0.7);
}
void TeleopPeriodic() override {
@@ -38,17 +40,18 @@ class Robot : public frc::TimedRobot {
// toward the goal while obeying the constraints.
m_setpoint = profile.Calculate(kDt);
// Run controller with profiled setpoint and update motor output
double output = m_controller.Calculate(m_encoder.GetDistance(),
m_setpoint.position.to<double>());
m_motor.Set(output);
// Send setpoint to offboard controller PID
m_motor.SetSetpoint(ExampleSmartMotorController::PIDMode::kPosition,
m_setpoint.position.to<double>(),
m_feedforward.Calculate(m_setpoint.velocity) / 12_V);
}
private:
frc::Joystick m_joystick{1};
frc::Encoder m_encoder{1, 2};
frc::PWMVictorSPX m_motor{1};
frc2::PIDController m_controller{1.3, 0.0, 0.7, kDt};
ExampleSmartMotorController m_motor{1};
frc::SimpleMotorFeedforward<units::meters> m_feedforward{
// Note: These gains are fake, and will have to be tuned for your robot.
1_V, 1.5_V * 1_s / 1_m};
frc::TrapezoidProfile<units::meters>::Constraints m_constraints{1.75_mps,
0.75_mps_sq};

View File

@@ -0,0 +1,87 @@
/*----------------------------------------------------------------------------*/
/* 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/SpeedController.h>
/**
* A simplified stub class that simulates the API of a common "smart" motor
* controller.
*
* <p>Has no actual functionality.
*/
class ExampleSmartMotorController : public frc::SpeedController {
public:
enum PIDMode { kPosition, kVelocity, kMovementWitchcraft };
/**
* Creates a new ExampleSmartMotorController.
*
* @param port The port for the controller.
*/
explicit ExampleSmartMotorController(int port) {}
/**
* Example method for setting the PID gains of the smart controller.
*
* @param kp The proportional gain.
* @param ki The integral gain.
* @param kd The derivative gain.
*/
void SetPID(double kp, double ki, double kd) {}
/**
* Example method for setting the setpoint of the smart controller in PID
* mode.
*
* @param mode The mode of the PID controller.
* @param setpoint The controller setpoint.
* @param arbFeedforward An arbitrary feedforward output (from -1 to 1).
*/
void SetSetpoint(PIDMode mode, double setpoint, double arbFeedforward) {}
/**
* Places this motor controller in follower mode.
*
* @param master The master to follow.
*/
void Follow(ExampleSmartMotorController master) {}
/**
* Returns the encoder distance.
*
* @return The current encoder distance.
*/
double GetEncoderDistance() { return 0; }
/**
* Returns the encoder rate.
*
* @return The current encoder rate.
*/
double GetEncoderRate() { return 0; }
/**
* Resets the encoder to zero distance.
*/
void ResetEncoder() {}
void Set(double speed) override {}
double Get() const override { return 0; }
void SetInverted(bool isInverted) override {}
bool GetInverted() const override { return false; }
void Disable() override {}
void StopMotor() override {}
void PIDWrite(double output) override {}
};

View File

@@ -8,6 +8,9 @@
#include "RobotContainer.h"
#include <frc/shuffleboard/Shuffleboard.h>
#include <frc2/command/PIDCommand.h>
#include <frc2/command/ParallelRaceGroup.h>
#include <frc2/command/RunCommand.h>
#include <frc2/command/button/JoystickButton.h>
RobotContainer::RobotContainer() {
@@ -29,16 +32,39 @@ RobotContainer::RobotContainer() {
void RobotContainer::ConfigureButtonBindings() {
// Configure your button bindings here
// Assorted commands to be bound to buttons
// Stabilize robot to drive straight with gyro when left bumper is held
frc2::JoystickButton(&m_driverController, 5).WhenHeld(&m_stabilizeDriving);
frc2::JoystickButton(&m_driverController, 5)
.WhenHeld(frc2::PIDCommand{
frc2::PIDController{dc::kStabilizationP, dc::kStabilizationI,
dc::kStabilizationD},
// Close the loop on the turn rate
[this] { return m_drive.GetTurnRate(); },
// Setpoint is 0
0,
// Pipe the output to the turning controls
[this](double output) {
m_drive.ArcadeDrive(m_driverController.GetY(
frc::GenericHID::JoystickHand::kLeftHand),
output);
},
// Require the robot drive
{&m_drive}});
// Turn to 90 degrees when the 'X' button is pressed
frc2::JoystickButton(&m_driverController, 3).WhenPressed(&m_turnTo90);
frc2::JoystickButton(&m_driverController, 3)
.WhenPressed(TurnToAngle{90_deg, &m_drive}.WithTimeout(5_s));
// Turn to -90 degrees with a profile when the 'A' button is pressed, with a 5
// second timeout
frc2::JoystickButton(&m_driverController, 1)
.WhenPressed(TurnToAngle{90_deg, &m_drive}.WithTimeout(5_s));
// While holding the shoulder button, drive at half speed
frc2::JoystickButton(&m_driverController, 6)
.WhenPressed(&m_driveHalfSpeed)
.WhenReleased(&m_driveFullSpeed);
.WhenPressed(frc2::InstantCommand{[this] { m_drive.SetMaxOutput(0.5); }})
.WhenReleased(frc2::InstantCommand{[this] { m_drive.SetMaxOutput(1); }});
}
frc2::Command* RobotContainer::GetAutonomousCommand() {

View File

@@ -11,12 +11,12 @@
using namespace DriveConstants;
TurnToAngle::TurnToAngle(double targetAngleDegrees, DriveSubsystem* drive)
TurnToAngle::TurnToAngle(units::degree_t target, DriveSubsystem* drive)
: CommandHelper(frc2::PIDController(kTurnP, kTurnI, kTurnD),
// Close loop on heading
[drive] { return drive->GetHeading(); },
[drive] { return drive->GetHeading().to<double>(); },
// Set reference to target
targetAngleDegrees,
target.to<double>(),
// Pipe output to turn robot
[drive](double output) { drive->ArcadeDrive(0, output); },
// Require the drive
@@ -26,9 +26,10 @@ TurnToAngle::TurnToAngle(double targetAngleDegrees, DriveSubsystem* drive)
// Set the controller tolerance - the delta tolerance ensures the robot is
// stationary at the setpoint before it is considered as having reached the
// reference
m_controller.SetTolerance(kTurnToleranceDeg, kTurnRateToleranceDegPerS);
m_controller.SetTolerance(kTurnTolerance.to<double>(),
kTurnRateTolerance.to<double>());
AddRequirements({drive});
}
bool TurnToAngle::IsFinished() { return m_controller.AtSetpoint(); }
bool TurnToAngle::IsFinished() { return GetController().AtSetpoint(); }

View File

@@ -0,0 +1,39 @@
/*----------------------------------------------------------------------------*/
/* 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 "commands/TurnToAngleProfiled.h"
#include <frc/controller/ProfiledPIDController.h>
using namespace DriveConstants;
TurnToAngleProfiled::TurnToAngleProfiled(units::degree_t target,
DriveSubsystem* drive)
: CommandHelper(
frc::ProfiledPIDController<units::radians>(
kTurnP, kTurnI, kTurnD, {kMaxTurnRate, kMaxTurnAcceleration}),
// Close loop on heading
[drive] { return drive->GetHeading(); },
// Set reference to target
target,
// Pipe output to turn robot
[drive](double output, auto setpointState) {
drive->ArcadeDrive(0, output);
},
// Require the drive
{drive}) {
// Set the controller to be continuous (because it is an angle controller)
GetController().EnableContinuousInput(-180_deg, 180_deg);
// Set the controller tolerance - the delta tolerance ensures the robot is
// stationary at the setpoint before it is considered as having reached the
// reference
GetController().SetTolerance(kTurnTolerance, kTurnRateTolerance);
AddRequirements({drive});
}
bool TurnToAngleProfiled::IsFinished() { return GetController().AtGoal(); }

View File

@@ -46,8 +46,9 @@ void DriveSubsystem::SetMaxOutput(double maxOutput) {
m_drive.SetMaxOutput(maxOutput);
}
double DriveSubsystem::GetHeading() {
return std::remainder(m_gyro.GetAngle(), 360) * (kGyroReversed ? -1.0 : 1.0);
units::degree_t DriveSubsystem::GetHeading() {
return units::degree_t(std::remainder(m_gyro.GetAngle(), 360) *
(kGyroReversed ? -1.0 : 1.0));
}
double DriveSubsystem::GetTurnRate() {

View File

@@ -7,6 +7,7 @@
#pragma once
#include <units/units.h>
#include <wpi/math>
/**
@@ -45,8 +46,11 @@ constexpr double kTurnP = 1;
constexpr double kTurnI = 0;
constexpr double kTurnD = 0;
constexpr double kTurnToleranceDeg = 5;
constexpr double kTurnRateToleranceDegPerS = 10; // degrees per second
constexpr auto kTurnTolerance = 5_deg;
constexpr auto kTurnRateTolerance = 10_deg_per_s;
constexpr auto kMaxTurnRate = 100_deg_per_s;
constexpr auto kMaxTurnAcceleration = 300_deg_per_s / 1_s;
} // namespace DriveConstants
namespace AutoConstants {

View File

@@ -12,9 +12,6 @@
#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 "commands/TurnToAngle.h"
@@ -45,34 +42,6 @@ class RobotContainer {
// The robot's subsystems
DriveSubsystem m_drive;
// Assorted commands to be bound to buttons
// Turn to 90 degrees, with a 5 second timeout
frc2::ParallelRaceGroup m_turnTo90 =
TurnToAngle{90, &m_drive}.WithTimeout(5_s);
// Stabilize the robot while driving
frc2::PIDCommand m_stabilizeDriving{
frc2::PIDController{dc::kStabilizationP, dc::kStabilizationI,
dc::kStabilizationD},
// Close the loop on the turn rate
[this] { return m_drive.GetTurnRate(); },
// Setpoint is 0
0,
// Pipe the output to the turning controls
[this](double output) {
m_drive.ArcadeDrive(
m_driverController.GetY(frc::GenericHID::JoystickHand::kLeftHand),
output);
},
// Require the robot drive
{&m_drive}};
frc2::InstantCommand m_driveHalfSpeed{[this] { m_drive.SetMaxOutput(0.5); },
{}};
frc2::InstantCommand m_driveFullSpeed{[this] { m_drive.SetMaxOutput(1); },
{}};
// The chooser for the autonomous routines
frc::SendableChooser<frc2::Command*> m_chooser;

View File

@@ -23,7 +23,7 @@ class TurnToAngle : public frc2::CommandHelper<frc2::PIDCommand, TurnToAngle> {
* @param targetAngleDegrees The angle to turn to
* @param drive The drive subsystem to use
*/
TurnToAngle(double targetAngleDegrees, DriveSubsystem* drive);
TurnToAngle(units::degree_t target, DriveSubsystem* drive);
bool IsFinished() override;
};

View File

@@ -0,0 +1,33 @@
/*----------------------------------------------------------------------------*/
/* 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 <frc2/command/CommandHelper.h>
#include <frc2/command/ProfiledPIDCommand.h>
#include "subsystems/DriveSubsystem.h"
/**
* A command that will turn the robot to the specified angle using a motion
* profile.
*/
class TurnToAngleProfiled
: public frc2::CommandHelper<frc2::ProfiledPIDCommand<units::radians>,
TurnToAngleProfiled> {
public:
/**
* Turns to robot to the specified angle using a motion profile.
*
* @param targetAngleDegrees The angle to turn to
* @param drive The drive subsystem to use
*/
TurnToAngleProfiled(units::degree_t targetAngleDegrees,
DriveSubsystem* drive);
bool IsFinished() override;
};

View File

@@ -13,6 +13,7 @@
#include <frc/SpeedControllerGroup.h>
#include <frc/drive/DifferentialDrive.h>
#include <frc2/command/SubsystemBase.h>
#include <units/units.h>
#include "Constants.h"
@@ -74,7 +75,7 @@ class DriveSubsystem : public frc2::SubsystemBase {
*
* @return the robot's heading in degrees, from 180 to 180
*/
double GetHeading();
units::degree_t GetHeading();
/**
* Returns the turn rate of the robot.

View File

@@ -508,5 +508,29 @@
"foldername": "ArmBot",
"gradlebase": "cpp",
"commandversion": 2
},
{
"name": "ArmBotOffboard",
"description": "An example command-based robot demonstrating the use of a TrapezoidProfileSubsystem to control an arm with an offboard PID.",
"tags": [
"ArmBotOffboard",
"PID",
"Motion Profile"
],
"foldername": "ArmBotOffboard",
"gradlebase": "cpp",
"commandversion": 2
},
{
"name": "DriveDistanceOffboard",
"description": "An example command-based robot demonstrating the use of a TrapezoidProfileCommand to drive a robot a set distance with offboard PID on the drive.",
"tags": [
"DriveDistance",
"PID",
"Motion Profile"
],
"foldername": "DriveDistanceOffboard",
"gradlebase": "cpp",
"commandversion": 2
}
]