[examples] Add simple differential drive simulation example (#2918)

This provides an example of using the differential drive simulator without needing to use the command-based library.
This commit is contained in:
Prateek Machiraju
2020-12-08 01:32:42 -05:00
committed by GitHub
parent 4f40d991ea
commit 558e37c412
8 changed files with 539 additions and 0 deletions

View File

@@ -0,0 +1,65 @@
/*----------------------------------------------------------------------------*/
/* 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::ResetOdometry(const frc::Pose2d& pose) {
m_leftEncoder.Reset();
m_rightEncoder.Reset();
m_drivetrainSimulator.SetPose(pose);
m_odometry.ResetPosition(pose, m_gyro.GetRotation2d());
}
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.GetLeftPosition().to<double>());
m_leftEncoderSim.SetRate(
m_drivetrainSimulator.GetLeftVelocity().to<double>());
m_rightEncoderSim.SetDistance(
m_drivetrainSimulator.GetRightPosition().to<double>());
m_rightEncoderSim.SetRate(
m_drivetrainSimulator.GetRightVelocity().to<double>());
m_gyroSim.SetAngle(
-m_drivetrainSimulator.GetHeading().Degrees().to<double>());
m_fieldSim.SetRobotPose(m_odometry.GetPose());
}

View File

@@ -0,0 +1,76 @@
/*----------------------------------------------------------------------------*/
/* 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 <frc/controller/RamseteController.h>
#include <frc/trajectory/TrajectoryGenerator.h>
#include <frc2/Timer.h>
#include "Drivetrain.h"
class Robot : public frc::TimedRobot {
public:
void RobotInit() override {
m_trajectory = frc::TrajectoryGenerator::GenerateTrajectory(
frc::Pose2d(2_m, 2_m, 0_rad), {}, frc::Pose2d(6_m, 4_m, 0_rad),
frc::TrajectoryConfig(2_mps, 2_mps_sq));
}
void AutonomousInit() override {
m_timer.Reset();
m_timer.Start();
m_drive.ResetOdometry(m_trajectory.InitialPose());
}
void AutonomousPeriodic() override {
auto elapsed = m_timer.Get();
auto reference = m_trajectory.Sample(elapsed);
auto speeds = m_ramsete.Calculate(m_drive.GetPose(), reference);
m_drive.Drive(speeds.vx, speeds.omega);
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;
frc::Trajectory m_trajectory;
frc::RamseteController m_ramsete;
frc2::Timer m_timer;
};
#ifndef RUNNING_FRC_TESTS
int main() { return frc::StartRobot<Robot>(); }
#endif

View File

@@ -0,0 +1,107 @@
/*----------------------------------------------------------------------------*/
/* 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/smartdashboard/Field2d.h>
#include <frc/smartdashboard/SmartDashboard.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();
m_rightGroup.SetInverted(true);
frc::SmartDashboard::PutData("Field", &m_fieldSim);
}
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 ResetOdometry(const frc::Pose2d& pose);
frc::Pose2d GetPose() const { return m_odometry.GetPose(); }
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{8.5, 0.0, 0.0};
frc2::PIDController m_rightPIDController{8.5, 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_V / 1_mps, 0.2_V / 1_mps_sq, 1.5_V / 1_rad_per_s,
0.3_V / 1_rad_per_s_sq);
frc::sim::DifferentialDrivetrainSim m_drivetrainSimulator{
m_drivetrainSystem, kTrackWidth, frc::DCMotor::CIM(2), 8, 2_in};
};

View File

@@ -676,6 +676,24 @@
"mainclass": "Main",
"commandversion": 2
},
{
"name": "SimpleDifferentialDriveSimulation",
"description": "An example of a minimal drivetrain simulation project without the command-based library.",
"tags": [
"Differential Drive",
"State space",
"Digital",
"Sensors",
"Simulation",
"Physics",
"Drivetrain",
"Field2d"
],
"foldername": "SimpleDifferentialDriveSimulation",
"gradlebase": "cpp",
"mainclass": "Main",
"commandversion": 2
},
{
"name": "StateSpaceDriveSimulation",
"description": "Demonstrates the use of physics simulation with a differential drivetrain and the Field2d class.",