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