[wpilib] Add physics simulation support with state-space (#2615)

This includes physics simulation support for arms/elevator models, as well as differential drivetrains.

Swerve might be added at a later date.

Co-authored-by: Claudius Tewari <cttewari@gmail.com>
Co-authored-by: Prateek Machiraju <prateek.machiraju@gmail.com>
Co-authored-by: Tyler Veness <calcmogul@gmail.com>
This commit is contained in:
Matt
2020-09-20 09:39:52 -07:00
committed by GitHub
parent 0503225928
commit b61f08d3fa
43 changed files with 3787 additions and 31 deletions

View File

@@ -0,0 +1,102 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2020 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/Encoder.h>
#include <frc/GenericHID.h>
#include <frc/Joystick.h>
#include <frc/PWMVictorSPX.h>
#include <frc/RobotController.h>
#include <frc/StateSpaceUtil.h>
#include <frc/TimedRobot.h>
#include <frc/controller/PIDController.h>
#include <frc/simulation/BatterySim.h>
#include <frc/simulation/EncoderSim.h>
#include <frc/simulation/RoboRioSim.h>
#include <frc/simulation/SingleJointedArmSim.h>
#include <frc/system/plant/LinearSystemId.h>
#include <units/angle.h>
#include <units/moment_of_inertia.h>
#include <wpi/math>
/**
* This is a sample program to demonstrate how to use a state-space controller
* to control an arm.
*/
class Robot : public frc::TimedRobot {
static constexpr int kMotorPort = 0;
static constexpr int kEncoderAChannel = 0;
static constexpr int kEncoderBChannel = 1;
static constexpr int kJoystickPort = 0;
// The P gain for the PID controller that drives this arm.
static constexpr double kArmKp = 5.0;
// distance per pulse = (angle per revolution) / (pulses per revolution)
// = (2 * PI rads) / (4096 pulses)
static constexpr double kArmEncoderDistPerPulse =
2.0 * wpi::math::pi / 4096.0;
// The arm gearbox represents a gerbox containing two Vex 775pro motors.
frc::DCMotor m_armGearbox = frc::DCMotor::Vex775Pro(2);
// Standard classes for controlling our arm
frc2::PIDController m_controller{kArmKp, 0, 0};
frc::Encoder m_encoder{kEncoderAChannel, kEncoderBChannel};
frc::PWMVictorSPX m_motor{kMotorPort};
frc::Joystick m_joystick{kJoystickPort};
// Simulation classes help us simulate what's going on, including gravity.
// This sim represents an arm with 2 775s, a 100:1 reduction, a mass of 5kg,
// 30in overall arm length, range of motion nin [-180, 0] degrees, and noise
// with a standard deviation of 0.5 degrees.
frc::sim::SingleJointedArmSim m_armSim{
m_armGearbox, 100.0, 5_kg, 30_in,
-180_deg, 0_deg, true, {(0.5_deg).to<double>()}};
frc::sim::EncoderSim m_encoderSim{m_encoder};
public:
void RobotInit() { m_encoder.SetDistancePerPulse(kArmEncoderDistPerPulse); }
void SimulationPeriodic() {
// In this method, we update our simulation of what our arm is doing
// First, we set our "inputs" (voltages)
m_armSim.SetInput(frc::MakeMatrix<1, 1>(
m_motor.Get() * frc::RobotController::GetInputVoltage()));
// Next, we update it. The standard loop time is 20ms.
m_armSim.Update(20_ms);
// Finally, we set our simulated encoder's readings and simulated battery
// voltage
m_encoderSim.SetDistance(m_armSim.GetAngle().to<double>());
// SimBattery estimates loaded battery voltages
frc::sim::RoboRioSim::SetVInVoltage(
frc::sim::BatterySim::Calculate({m_armSim.GetCurrentDraw()})
.to<double>());
}
void TeleopPeriodic() {
if (m_joystick.GetTrigger()) {
// Here, we run PID control like normal, with a constant setpoint of 30in.
double pidOutput =
m_controller.Calculate(m_encoder.GetDistance(), (30_in).to<double>());
m_motor.SetVoltage(units::volt_t(pidOutput));
} else {
// Otherwise, we disable the motor.
m_motor.Set(0.0);
}
}
void DisabledInit() {
// This just makes sure that our simulation code knows that the motor's off.
m_motor.Set(0.0);
}
};
#ifndef RUNNING_FRC_TESTS
int main() { return frc::StartRobot<Robot>(); }
#endif

View File

@@ -0,0 +1,58 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019-2020 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 "Drivetrain.h"
#include <frc/RobotController.h>
void Drivetrain::SetSpeeds(const frc::DifferentialDriveWheelSpeeds& speeds) {
auto leftFeedforward = m_feedforward.Calculate(speeds.left);
auto rightFeedforward = m_feedforward.Calculate(speeds.right);
double leftOutput = m_leftPIDController.Calculate(m_leftEncoder.GetRate(),
speeds.left.to<double>());
double rightOutput = m_rightPIDController.Calculate(
m_rightEncoder.GetRate(), speeds.right.to<double>());
m_leftGroup.SetVoltage(units::volt_t{leftOutput} + leftFeedforward);
m_rightGroup.SetVoltage(units::volt_t{rightOutput} + rightFeedforward);
}
void Drivetrain::Drive(units::meters_per_second_t xSpeed,
units::radians_per_second_t rot) {
SetSpeeds(m_kinematics.ToWheelSpeeds({xSpeed, 0_mps, rot}));
}
void Drivetrain::UpdateOdometry() {
m_odometry.Update(m_gyro.GetRotation2d(),
units::meter_t(m_leftEncoder.GetDistance()),
units::meter_t(m_rightEncoder.GetDistance()));
}
void Drivetrain::SimulationPeriodic() {
// To update our simulation, we set motor voltage inputs, update the
// simulation, and write the simulated positions and velocities to our
// simulated encoder and gyro. We negate the right side so that positive
// voltages make the right side move forward.
m_drivetrainSimulator.SetInputs(units::volt_t{m_leftLeader.Get()} *
frc::RobotController::GetInputVoltage(),
units::volt_t{-m_rightLeader.Get()} *
frc::RobotController::GetInputVoltage());
m_drivetrainSimulator.Update(20_ms);
m_leftEncoderSim.SetDistance(m_drivetrainSimulator.GetState(
frc::sim::DifferentialDrivetrainSim::State::kLeftPosition));
m_leftEncoderSim.SetRate(m_drivetrainSimulator.GetState(
frc::sim::DifferentialDrivetrainSim::State::kLeftVelocity));
m_rightEncoderSim.SetDistance(m_drivetrainSimulator.GetState(
frc::sim::DifferentialDrivetrainSim::State::kRightPosition));
m_rightEncoderSim.SetRate(m_drivetrainSimulator.GetState(
frc::sim::DifferentialDrivetrainSim::State::kRightVelocity));
m_gyroSim.SetAngle(
-m_drivetrainSimulator.GetHeading().Degrees().to<double>());
m_fieldSim.SetRobotPose(m_odometry.GetPose());
}

View File

@@ -0,0 +1,54 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019-2020 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/SlewRateLimiter.h>
#include <frc/TimedRobot.h>
#include <frc/XboxController.h>
#include "Drivetrain.h"
class Robot : public frc::TimedRobot {
public:
void AutonomousPeriodic() override {
TeleopPeriodic();
m_drive.UpdateOdometry();
}
void TeleopPeriodic() override {
// Get the x speed. We are inverting this because Xbox controllers return
// negative values when we push forward.
const auto xSpeed = -m_speedLimiter.Calculate(
m_controller.GetY(frc::GenericHID::kLeftHand)) *
Drivetrain::kMaxSpeed;
// Get the rate of angular rotation. We are inverting this because we want a
// positive value when we pull to the left (remember, CCW is positive in
// mathematics). Xbox controllers return positive values when you pull to
// the right by default.
auto rot = -m_rotLimiter.Calculate(
m_controller.GetX(frc::GenericHID::kRightHand)) *
Drivetrain::kMaxAngularSpeed;
m_drive.Drive(xSpeed, rot);
}
void SimulationPeriodic() override { m_drive.SimulationPeriodic(); }
private:
frc::XboxController m_controller{0};
// Slew rate limiters to make joystick inputs more gentle; 1/3 sec from 0
// to 1.
frc::SlewRateLimiter<units::scalar> m_speedLimiter{3 / 1_s};
frc::SlewRateLimiter<units::scalar> m_rotLimiter{3 / 1_s};
Drivetrain m_drive;
};
#ifndef RUNNING_FRC_TESTS
int main() { return frc::StartRobot<Robot>(); }
#endif

View File

@@ -0,0 +1,97 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019-2020 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/AnalogGyro.h>
#include <frc/Encoder.h>
#include <frc/PWMVictorSPX.h>
#include <frc/SpeedControllerGroup.h>
#include <frc/controller/PIDController.h>
#include <frc/controller/SimpleMotorFeedforward.h>
#include <frc/kinematics/DifferentialDriveKinematics.h>
#include <frc/kinematics/DifferentialDriveOdometry.h>
#include <frc/simulation/AnalogGyroSim.h>
#include <frc/simulation/DifferentialDrivetrainSim.h>
#include <frc/simulation/EncoderSim.h>
#include <frc/simulation/Field2d.h>
#include <frc/system/plant/LinearSystemId.h>
#include <units/angle.h>
#include <units/angular_velocity.h>
#include <units/length.h>
#include <units/velocity.h>
#include <wpi/math>
/**
* Represents a differential drive style drivetrain.
*/
class Drivetrain {
public:
Drivetrain() {
m_gyro.Reset();
// Set the distance per pulse for the drive encoders. We can simply use the
// distance traveled for one rotation of the wheel divided by the encoder
// resolution.
m_leftEncoder.SetDistancePerPulse(2 * wpi::math::pi * kWheelRadius /
kEncoderResolution);
m_rightEncoder.SetDistancePerPulse(2 * wpi::math::pi * kWheelRadius /
kEncoderResolution);
m_leftEncoder.Reset();
m_rightEncoder.Reset();
}
static constexpr units::meters_per_second_t kMaxSpeed =
3.0_mps; // 3 meters per second
static constexpr units::radians_per_second_t kMaxAngularSpeed{
wpi::math::pi}; // 1/2 rotation per second
void SetSpeeds(const frc::DifferentialDriveWheelSpeeds& speeds);
void Drive(units::meters_per_second_t xSpeed,
units::radians_per_second_t rot);
void UpdateOdometry();
void SimulationPeriodic();
private:
static constexpr units::meter_t kTrackWidth = 0.381_m * 2;
static constexpr double kWheelRadius = 0.0508; // meters
static constexpr int kEncoderResolution = 4096;
frc::PWMVictorSPX m_leftLeader{1};
frc::PWMVictorSPX m_leftFollower{2};
frc::PWMVictorSPX m_rightLeader{3};
frc::PWMVictorSPX m_rightFollower{4};
frc::SpeedControllerGroup m_leftGroup{m_leftLeader, m_leftFollower};
frc::SpeedControllerGroup m_rightGroup{m_rightLeader, m_rightFollower};
frc::Encoder m_leftEncoder{0, 1};
frc::Encoder m_rightEncoder{2, 3};
frc2::PIDController m_leftPIDController{1.0, 0.0, 0.0};
frc2::PIDController m_rightPIDController{1.0, 0.0, 0.0};
frc::AnalogGyro m_gyro{0};
frc::DifferentialDriveKinematics m_kinematics{kTrackWidth};
frc::DifferentialDriveOdometry m_odometry{m_gyro.GetRotation2d()};
// Gains are for example purposes only - must be determined for your own
// robot!
frc::SimpleMotorFeedforward<units::meters> m_feedforward{1_V, 3_V / 1_mps};
// Simulation classes help us simulate our robot
frc::sim::AnalogGyroSim m_gyroSim{m_gyro};
frc::sim::EncoderSim m_leftEncoderSim{m_leftEncoder};
frc::sim::EncoderSim m_rightEncoderSim{m_rightEncoder};
frc::Field2d m_fieldSim{};
frc::LinearSystem<2, 2, 2> m_drivetrainSystem =
frc::LinearSystemId::IdentifyDrivetrainSystem(1.98, 0.2, 1.5, 0.3);
frc::sim::DifferentialDrivetrainSim m_drivetrainSimulator{
m_drivetrainSystem, kTrackWidth, frc::DCMotor::CIM(2), 8, 2_in};
};

View File

@@ -0,0 +1,109 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2020 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/Encoder.h>
#include <frc/GenericHID.h>
#include <frc/Joystick.h>
#include <frc/PWMVictorSPX.h>
#include <frc/RobotController.h>
#include <frc/StateSpaceUtil.h>
#include <frc/TimedRobot.h>
#include <frc/controller/PIDController.h>
#include <frc/simulation/BatterySim.h>
#include <frc/simulation/ElevatorSim.h>
#include <frc/simulation/EncoderSim.h>
#include <frc/simulation/RoboRioSim.h>
#include <frc/system/plant/LinearSystemId.h>
#include <units/angle.h>
#include <units/moment_of_inertia.h>
#include <wpi/math>
/**
* This is a sample program to demonstrate how to use a state-space controller
* to control an arm.
*/
class Robot : public frc::TimedRobot {
static constexpr int kMotorPort = 0;
static constexpr int kEncoderAChannel = 0;
static constexpr int kEncoderBChannel = 1;
static constexpr int kJoystickPort = 0;
static constexpr double kElevatorKp = 5.0;
static constexpr double kElevatorGearing = 10.0;
static constexpr units::meter_t kElevatorDrumRadius = 2_in;
static constexpr units::kilogram_t kCarriageMass = 4.0_kg;
static constexpr units::meter_t kMinElevatorHeight = 0_in;
static constexpr units::meter_t kMaxElevatorHeight = 50_in;
// distance per pulse = (distance per revolution) / (pulses per revolution)
// = (Pi * D) / ppr
static constexpr double kArmEncoderDistPerPulse =
2.0 * wpi::math::pi * kElevatorDrumRadius.to<double>() / 4096.0;
// This gearbox represents a gearbox containing 4 Vex 775pro motors.
frc::DCMotor m_elevatorGearbox = frc::DCMotor::Vex775Pro(4);
// Standard classes for controlling our elevator
frc2::PIDController m_controller{kElevatorKp, 0, 0};
frc::Encoder m_encoder{kEncoderAChannel, kEncoderBChannel};
frc::PWMVictorSPX m_motor{kMotorPort};
frc::Joystick m_joystick{kJoystickPort};
// Simulation classes help us simulate what's going on, including gravity.
frc::sim::ElevatorSim m_elevatorSim{m_elevatorGearbox,
kCarriageMass,
kElevatorGearing,
kElevatorDrumRadius,
kMinElevatorHeight,
kMaxElevatorHeight,
true,
{0.01}};
frc::sim::EncoderSim m_encoderSim{m_encoder};
public:
void RobotInit() { m_encoder.SetDistancePerPulse(kArmEncoderDistPerPulse); }
void SimulationPeriodic() {
// In this method, we update our simulation of what our elevator is doing
// First, we set our "inputs" (voltages)
m_elevatorSim.SetInput(frc::MakeMatrix<1, 1>(
m_motor.Get() * frc::RobotController::GetInputVoltage()));
// Next, we update it. The standard loop time is 20ms.
m_elevatorSim.Update(20_ms);
// Finally, we set our simulated encoder's readings and simulated battery
// voltage
m_encoderSim.SetDistance(m_elevatorSim.GetPosition().to<double>());
// SimBattery estimates loaded battery voltages
frc::sim::RoboRioSim::SetVInVoltage(
frc::sim::BatterySim::Calculate({m_elevatorSim.GetCurrentDraw()})
.to<double>());
}
void TeleopPeriodic() {
if (m_joystick.GetTrigger()) {
// Here, we run PID control like normal, with a constant setpoint of 30in.
double pidOutput =
m_controller.Calculate(m_encoder.GetDistance(), (30_in).to<double>());
m_motor.SetVoltage(units::volt_t(pidOutput));
} else {
// Otherwise, we disable the motor.
m_motor.Set(0.0);
}
}
void DisabledInit() {
// This just makes sure that our simulation code knows that the motor's off.
m_motor.Set(0.0);
}
};
#ifndef RUNNING_FRC_TESTS
int main() { return frc::StartRobot<Robot>(); }
#endif

View File

@@ -611,5 +611,55 @@
"gradlebase": "cpp",
"mainclass": "Main",
"commandversion": 2
},
{
"name": "ElevatorSimulation",
"description": "Demonstrates the use of physics simulation with a simple elevator.",
"tags": [
"Elevator",
"State space",
"Digital",
"Sensors",
"Simulation",
"Physics"
],
"foldername": "ElevatorSimulation",
"gradlebase": "cpp",
"mainclass": "Main",
"commandversion": 2
},
{
"name": "ArmSimulation",
"description": "Demonstrates the use of physics simulation with a simple single-jointed arm.",
"tags": [
"Arm",
"State space",
"Digital",
"Sensors",
"Simulation",
"Physics"
],
"foldername": "ArmSimulation",
"gradlebase": "cpp",
"mainclass": "Main",
"commandversion": 2
},
{
"name": "DifferentialDriveSimulation",
"description": "Demonstrates the use of physics simulation with a differential drivetrain and the Field2d class.",
"tags": [
"Differential Drive",
"State space",
"Digital",
"Sensors",
"Simulation",
"Physics",
"Drivetrain",
"Field2d"
],
"foldername": "DifferentialDriveSimulation",
"gradlebase": "cpp",
"mainclass": "Main",
"commandversion": 2
}
]