[wpilib] Add pose estimators (#2867)

Pose and state estimators can filter latency-compensated global measurements and fuse them with state-space drivetrain model information to estimate robot position. They are drop-in replacements for the existing odometry classes.

Co-authored-by: Declan Freeman-Gleason <declanfreemangleason@gmail.com>
Co-authored-by: Prateek Machiraju <prateek.machiraju@gmail.com>
Co-authored-by: Claudius Tewari <cttewari@gmail.com>
Co-authored-by: Matt <matthew.morley.ca@gmail.com>
This commit is contained in:
Declan Freeman-Gleason
2020-11-28 17:35:35 -05:00
committed by GitHub
parent 3413bfc06a
commit bc8f338771
58 changed files with 4958 additions and 39 deletions

View File

@@ -0,0 +1,45 @@
/*----------------------------------------------------------------------------*/
/* 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 <frc2/Timer.h>
#include "ExampleGlobalMeasurementSensor.h"
void Drivetrain::SetSpeeds(const frc::DifferentialDriveWheelSpeeds& speeds) {
const auto leftFeedforward = m_feedforward.Calculate(speeds.left);
const auto rightFeedforward = m_feedforward.Calculate(speeds.right);
const double leftOutput = m_leftPIDController.Calculate(
m_leftEncoder.GetRate(), speeds.left.to<double>());
const 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_poseEstimator.Update(m_gyro.GetRotation2d(),
{units::meters_per_second_t(m_leftEncoder.GetRate()),
units::meters_per_second_t(m_rightEncoder.GetRate())},
units::meter_t(m_leftEncoder.GetDistance()),
units::meter_t(m_rightEncoder.GetDistance()));
// Also apply vision measurements. We use 0.3 seconds in the past as an
// example -- on a real robot, this must be calculated based either on latency
// or timestamps.
m_poseEstimator.AddVisionMeasurement(
ExampleGlobalMeasurementSensor::GetEstimatedGlobalPose(
m_poseEstimator.GetEstimatedPosition()),
frc2::Timer::GetFPGATimestamp() - 0.3_s);
}

View File

@@ -0,0 +1,52 @@
/*----------------------------------------------------------------------------*/
/* 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.
const auto rot = -m_rotLimiter.Calculate(
m_controller.GetX(frc::GenericHID::kRightHand)) *
Drivetrain::kMaxAngularSpeed;
m_drive.Drive(xSpeed, rot);
}
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,88 @@
/*----------------------------------------------------------------------------*/
/* 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/estimator/DifferentialDrivePoseEstimator.h>
#include <frc/kinematics/DifferentialDriveKinematics.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.to<double>() / kEncoderResolution);
m_rightEncoder.SetDistancePerPulse(
2 * wpi::math::pi * kWheelRadius.to<double>() / 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();
private:
static constexpr units::meter_t kTrackWidth = 0.381_m * 2;
static constexpr units::meter_t kWheelRadius = 0.0508_m;
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};
// Gains are for example purposes only - must be determined for your own
// robot!
frc::DifferentialDrivePoseEstimator m_poseEstimator{
frc::Rotation2d(),
frc::Pose2d(),
{0.01, 0.01, 0.01, 0.01, 0.01},
{0.1, 0.1, 0.1},
{0.1, 0.1, 0.1}};
// 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};
};

View File

@@ -0,0 +1,27 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 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/StateSpaceUtil.h>
#include <frc/geometry/Pose2d.h>
/**
* This dummy class represents a global measurement sensor, such as a computer
* vision solution.
*/
class ExampleGlobalMeasurementSensor {
public:
static frc::Pose2d GetEstimatedGlobalPose(
const frc::Pose2d& estimatedRobotPose) {
auto randVec = frc::MakeWhiteNoiseVector(0.1, 0.1, 0.1);
return frc::Pose2d(estimatedRobotPose.X() + units::meter_t(randVec(0)),
estimatedRobotPose.Y() + units::meter_t(randVec(1)),
estimatedRobotPose.Rotation() +
frc::Rotation2d(units::radian_t(randVec(3))));
}
};

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 <frc2/Timer.h>
#include "ExampleGlobalMeasurementSensor.h"
frc::MecanumDriveWheelSpeeds Drivetrain::GetCurrentState() const {
return {units::meters_per_second_t(m_frontLeftEncoder.GetRate()),
units::meters_per_second_t(m_frontRightEncoder.GetRate()),
units::meters_per_second_t(m_backLeftEncoder.GetRate()),
units::meters_per_second_t(m_backRightEncoder.GetRate())};
}
void Drivetrain::SetSpeeds(const frc::MecanumDriveWheelSpeeds& wheelSpeeds) {
std::function<void(units::meters_per_second_t, const frc::Encoder&,
frc2::PIDController&, frc::PWMVictorSPX&)>
calcAndSetSpeeds =
[&m_feedforward = m_feedforward](units::meters_per_second_t speed,
const auto& encoder,
auto& controller, auto& motor) {
auto feedforward = m_feedforward.Calculate(speed);
double output =
controller.Calculate(encoder.GetRate(), speed.to<double>());
motor.SetVoltage(units::volt_t{output} + feedforward);
};
calcAndSetSpeeds(wheelSpeeds.frontLeft, m_frontLeftEncoder,
m_frontLeftPIDController, m_frontLeftMotor);
calcAndSetSpeeds(wheelSpeeds.frontRight, m_frontRightEncoder,
m_frontRightPIDController, m_frontRightMotor);
calcAndSetSpeeds(wheelSpeeds.rearLeft, m_backLeftEncoder,
m_backLeftPIDController, m_backLeftMotor);
calcAndSetSpeeds(wheelSpeeds.rearRight, m_backRightEncoder,
m_backRightPIDController, m_backRightMotor);
}
void Drivetrain::Drive(units::meters_per_second_t xSpeed,
units::meters_per_second_t ySpeed,
units::radians_per_second_t rot, bool fieldRelative) {
auto wheelSpeeds = m_kinematics.ToWheelSpeeds(
fieldRelative ? frc::ChassisSpeeds::FromFieldRelativeSpeeds(
xSpeed, ySpeed, rot, m_gyro.GetRotation2d())
: frc::ChassisSpeeds{xSpeed, ySpeed, rot});
wheelSpeeds.Normalize(kMaxSpeed);
SetSpeeds(wheelSpeeds);
}
void Drivetrain::UpdateOdometry() {
m_poseEstimator.Update(m_gyro.GetRotation2d(), GetCurrentState());
// Also apply vision measurements. We use 0.3 seconds in the past as an
// example -- on a real robot, this must be calculated based either on latency
// or timestamps.
m_poseEstimator.AddVisionMeasurement(
ExampleGlobalMeasurementSensor::GetEstimatedGlobalPose(
m_poseEstimator.GetEstimatedPosition()),
frc2::Timer::GetFPGATimestamp() - 0.3_s);
}

View File

@@ -0,0 +1,61 @@
/*----------------------------------------------------------------------------*/
/* 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 {
DriveWithJoystick(false);
m_mecanum.UpdateOdometry();
}
void TeleopPeriodic() override { DriveWithJoystick(true); }
private:
frc::XboxController m_controller{0};
Drivetrain m_mecanum;
// Slew rate limiters to make joystick inputs more gentle; 1/3 sec from 0
// to 1.
frc::SlewRateLimiter<units::scalar> m_xspeedLimiter{3 / 1_s};
frc::SlewRateLimiter<units::scalar> m_yspeedLimiter{3 / 1_s};
frc::SlewRateLimiter<units::scalar> m_rotLimiter{3 / 1_s};
void DriveWithJoystick(bool fieldRelative) {
// Get the x speed. We are inverting this because Xbox controllers return
// negative values when we push forward.
const auto xSpeed = -m_xspeedLimiter.Calculate(
m_controller.GetY(frc::GenericHID::kLeftHand)) *
Drivetrain::kMaxSpeed;
// Get the y speed or sideways/strafe speed. We are inverting this because
// we want a positive value when we pull to the left. Xbox controllers
// return positive values when you pull to the right by default.
const auto ySpeed = -m_yspeedLimiter.Calculate(
m_controller.GetX(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.
const auto rot = -m_rotLimiter.Calculate(
m_controller.GetX(frc::GenericHID::kRightHand)) *
Drivetrain::kMaxAngularSpeed;
m_mecanum.Drive(xSpeed, ySpeed, rot, fieldRelative);
}
};
#ifndef RUNNING_FRC_TESTS
int main() { return frc::StartRobot<Robot>(); }
#endif

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. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc/AnalogGyro.h>
#include <frc/Encoder.h>
#include <frc/PWMVictorSPX.h>
#include <frc/controller/PIDController.h>
#include <frc/controller/SimpleMotorFeedforward.h>
#include <frc/estimator/MecanumDrivePoseEstimator.h>
#include <frc/geometry/Translation2d.h>
#include <frc/kinematics/MecanumDriveKinematics.h>
#include <frc/kinematics/MecanumDriveOdometry.h>
#include <frc/kinematics/MecanumDriveWheelSpeeds.h>
#include <wpi/math>
/**
* Represents a mecanum drive style drivetrain.
*/
class Drivetrain {
public:
Drivetrain() { m_gyro.Reset(); }
frc::MecanumDriveWheelSpeeds GetCurrentState() const;
void SetSpeeds(const frc::MecanumDriveWheelSpeeds& wheelSpeeds);
void Drive(units::meters_per_second_t xSpeed,
units::meters_per_second_t ySpeed, units::radians_per_second_t rot,
bool fieldRelative);
void UpdateOdometry();
static constexpr auto kMaxSpeed = 3.0_mps; // 3 meters per second
static constexpr units::radians_per_second_t kMaxAngularSpeed{
wpi::math::pi}; // 1/2 rotation per second
private:
frc::PWMVictorSPX m_frontLeftMotor{1};
frc::PWMVictorSPX m_frontRightMotor{2};
frc::PWMVictorSPX m_backLeftMotor{3};
frc::PWMVictorSPX m_backRightMotor{4};
frc::Encoder m_frontLeftEncoder{0, 1};
frc::Encoder m_frontRightEncoder{2, 3};
frc::Encoder m_backLeftEncoder{4, 5};
frc::Encoder m_backRightEncoder{6, 7};
frc::Translation2d m_frontLeftLocation{0.381_m, 0.381_m};
frc::Translation2d m_frontRightLocation{0.381_m, -0.381_m};
frc::Translation2d m_backLeftLocation{-0.381_m, 0.381_m};
frc::Translation2d m_backRightLocation{-0.381_m, -0.381_m};
frc2::PIDController m_frontLeftPIDController{1.0, 0.0, 0.0};
frc2::PIDController m_frontRightPIDController{1.0, 0.0, 0.0};
frc2::PIDController m_backLeftPIDController{1.0, 0.0, 0.0};
frc2::PIDController m_backRightPIDController{1.0, 0.0, 0.0};
frc::AnalogGyro m_gyro{0};
frc::MecanumDriveKinematics m_kinematics{
m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation,
m_backRightLocation};
// 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};
// Gains are for example purposes only - must be determined for your own
// robot!
frc::MecanumDrivePoseEstimator m_poseEstimator{
frc::Rotation2d(), frc::Pose2d(), m_kinematics,
{0.1, 0.1, 0.1}, {0.05}, {0.1, 0.1, 0.1}};
};

View File

@@ -0,0 +1,27 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 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/StateSpaceUtil.h>
#include <frc/geometry/Pose2d.h>
/**
* This dummy class represents a global measurement sensor, such as a computer
* vision solution.
*/
class ExampleGlobalMeasurementSensor {
public:
static frc::Pose2d GetEstimatedGlobalPose(
const frc::Pose2d& estimatedRobotPose) {
auto randVec = frc::MakeWhiteNoiseVector(0.1, 0.1, 0.1);
return frc::Pose2d(estimatedRobotPose.X() + units::meter_t(randVec(0)),
estimatedRobotPose.Y() + units::meter_t(randVec(1)),
estimatedRobotPose.Rotation() +
frc::Rotation2d(units::radian_t(randVec(3))));
}
};

View File

@@ -0,0 +1,44 @@
/*----------------------------------------------------------------------------*/
/* 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 <frc2/Timer.h>
#include "ExampleGlobalMeasurementSensor.h"
void Drivetrain::Drive(units::meters_per_second_t xSpeed,
units::meters_per_second_t ySpeed,
units::radians_per_second_t rot, bool fieldRelative) {
auto states = m_kinematics.ToSwerveModuleStates(
fieldRelative ? frc::ChassisSpeeds::FromFieldRelativeSpeeds(
xSpeed, ySpeed, rot, m_gyro.GetRotation2d())
: frc::ChassisSpeeds{xSpeed, ySpeed, rot});
m_kinematics.NormalizeWheelSpeeds(&states, kMaxSpeed);
auto [fl, fr, bl, br] = states;
m_frontLeft.SetDesiredState(fl);
m_frontRight.SetDesiredState(fr);
m_backLeft.SetDesiredState(bl);
m_backRight.SetDesiredState(br);
}
void Drivetrain::UpdateOdometry() {
m_poseEstimator.Update(m_gyro.GetRotation2d(), m_frontLeft.GetState(),
m_frontRight.GetState(), m_backLeft.GetState(),
m_backRight.GetState());
// Also apply vision measurements. We use 0.3 seconds in the past as an
// example -- on a real robot, this must be calculated based either on latency
// or timestamps.
m_poseEstimator.AddVisionMeasurement(
ExampleGlobalMeasurementSensor::GetEstimatedGlobalPose(
m_poseEstimator.GetEstimatedPosition()),
frc2::Timer::GetFPGATimestamp() - 0.3_s);
}

View File

@@ -0,0 +1,61 @@
/*----------------------------------------------------------------------------*/
/* 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 {
DriveWithJoystick(false);
m_swerve.UpdateOdometry();
}
void TeleopPeriodic() override { DriveWithJoystick(true); }
private:
frc::XboxController m_controller{0};
Drivetrain m_swerve;
// Slew rate limiters to make joystick inputs more gentle; 1/3 sec from 0
// to 1.
frc::SlewRateLimiter<units::scalar> m_xspeedLimiter{3 / 1_s};
frc::SlewRateLimiter<units::scalar> m_yspeedLimiter{3 / 1_s};
frc::SlewRateLimiter<units::scalar> m_rotLimiter{3 / 1_s};
void DriveWithJoystick(bool fieldRelative) {
// Get the x speed. We are inverting this because Xbox controllers return
// negative values when we push forward.
const auto xSpeed = -m_xspeedLimiter.Calculate(
m_controller.GetY(frc::GenericHID::kLeftHand)) *
Drivetrain::kMaxSpeed;
// Get the y speed or sideways/strafe speed. We are inverting this because
// we want a positive value when we pull to the left. Xbox controllers
// return positive values when you pull to the right by default.
const auto ySpeed = -m_yspeedLimiter.Calculate(
m_controller.GetX(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.
const auto rot = -m_rotLimiter.Calculate(
m_controller.GetX(frc::GenericHID::kRightHand)) *
Drivetrain::kMaxAngularSpeed;
m_swerve.Drive(xSpeed, ySpeed, rot, fieldRelative);
}
};
#ifndef RUNNING_FRC_TESTS
int main() { return frc::StartRobot<Robot>(); }
#endif

View File

@@ -0,0 +1,55 @@
/*----------------------------------------------------------------------------*/
/* 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 "SwerveModule.h"
#include <frc/geometry/Rotation2d.h>
#include <wpi/math>
SwerveModule::SwerveModule(const int driveMotorChannel,
const int turningMotorChannel)
: m_driveMotor(driveMotorChannel), m_turningMotor(turningMotorChannel) {
// Set the distance per pulse for the drive encoder. We can simply use the
// distance traveled for one rotation of the wheel divided by the encoder
// resolution.
m_driveEncoder.SetDistancePerPulse(
2 * wpi::math::pi * kWheelRadius.to<double>() / kEncoderResolution);
// Set the distance (in this case, angle) per pulse for the turning encoder.
// This is the the angle through an entire rotation (2 * wpi::math::pi)
// divided by the encoder resolution.
m_turningEncoder.SetDistancePerPulse(2 * wpi::math::pi / kEncoderResolution);
// Limit the PID Controller's input range between -pi and pi and set the input
// to be continuous.
m_turningPIDController.EnableContinuousInput(-units::radian_t(wpi::math::pi),
units::radian_t(wpi::math::pi));
}
frc::SwerveModuleState SwerveModule::GetState() const {
return {units::meters_per_second_t{m_driveEncoder.GetRate()},
frc::Rotation2d(units::radian_t(m_turningEncoder.Get()))};
}
void SwerveModule::SetDesiredState(const frc::SwerveModuleState& state) {
// Calculate the drive output from the drive PID controller.
const auto driveOutput = m_drivePIDController.Calculate(
m_driveEncoder.GetRate(), state.speed.to<double>());
const auto driveFeedforward = m_driveFeedforward.Calculate(state.speed);
// Calculate the turning motor output from the turning PID controller.
const auto turnOutput = m_turningPIDController.Calculate(
units::radian_t(m_turningEncoder.Get()), state.angle.Radians());
const auto turnFeedforward = m_turnFeedforward.Calculate(
m_turningPIDController.GetSetpoint().velocity);
// Set the motor outputs.
m_driveMotor.SetVoltage(units::volt_t{driveOutput} + driveFeedforward);
m_turningMotor.SetVoltage(units::volt_t{turnOutput} + turnFeedforward);
}

View File

@@ -0,0 +1,57 @@
/*----------------------------------------------------------------------------*/
/* 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/estimator/SwerveDrivePoseEstimator.h>
#include <frc/geometry/Translation2d.h>
#include <frc/kinematics/SwerveDriveKinematics.h>
#include <frc/kinematics/SwerveDriveOdometry.h>
#include <wpi/math>
#include "SwerveModule.h"
/**
* Represents a swerve drive style drivetrain.
*/
class Drivetrain {
public:
Drivetrain() { m_gyro.Reset(); }
void Drive(units::meters_per_second_t xSpeed,
units::meters_per_second_t ySpeed, units::radians_per_second_t rot,
bool fieldRelative);
void UpdateOdometry();
static constexpr auto kMaxSpeed = 3.0_mps; // 3 meters per second
static constexpr units::radians_per_second_t kMaxAngularSpeed{
wpi::math::pi}; // 1/2 rotation per second
private:
frc::Translation2d m_frontLeftLocation{+0.381_m, +0.381_m};
frc::Translation2d m_frontRightLocation{+0.381_m, -0.381_m};
frc::Translation2d m_backLeftLocation{-0.381_m, +0.381_m};
frc::Translation2d m_backRightLocation{-0.381_m, -0.381_m};
SwerveModule m_frontLeft{1, 2};
SwerveModule m_frontRight{2, 3};
SwerveModule m_backLeft{5, 6};
SwerveModule m_backRight{7, 8};
frc::AnalogGyro m_gyro{0};
frc::SwerveDriveKinematics<4> m_kinematics{
m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation,
m_backRightLocation};
// Gains are for example purposes only - must be determined for your own
// robot!
frc::SwerveDrivePoseEstimator<4> m_poseEstimator{
frc::Rotation2d(), frc::Pose2d(), m_kinematics,
{0.1, 0.1, 0.1}, {0.05}, {0.1, 0.1, 0.1}};
};

View File

@@ -0,0 +1,27 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 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/StateSpaceUtil.h>
#include <frc/geometry/Pose2d.h>
/**
* This dummy class represents a global measurement sensor, such as a computer
* vision solution.
*/
class ExampleGlobalMeasurementSensor {
public:
static frc::Pose2d GetEstimatedGlobalPose(
const frc::Pose2d& estimatedRobotPose) {
auto randVec = frc::MakeWhiteNoiseVector(0.1, 0.1, 0.1);
return frc::Pose2d(estimatedRobotPose.X() + units::meter_t(randVec(0)),
estimatedRobotPose.Y() + units::meter_t(randVec(1)),
estimatedRobotPose.Rotation() +
frc::Rotation2d(units::radian_t(randVec(3))));
}
};

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. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <frc/Encoder.h>
#include <frc/PWMVictorSPX.h>
#include <frc/controller/PIDController.h>
#include <frc/controller/ProfiledPIDController.h>
#include <frc/controller/SimpleMotorFeedforward.h>
#include <frc/kinematics/SwerveModuleState.h>
#include <units/angular_velocity.h>
#include <units/time.h>
#include <units/velocity.h>
#include <units/voltage.h>
#include <wpi/math>
class SwerveModule {
public:
SwerveModule(int driveMotorChannel, int turningMotorChannel);
frc::SwerveModuleState GetState() const;
void SetDesiredState(const frc::SwerveModuleState& state);
private:
static constexpr auto kWheelRadius = 0.0508_m;
static constexpr int kEncoderResolution = 4096;
static constexpr auto kModuleMaxAngularVelocity =
wpi::math::pi * 1_rad_per_s; // radians per second
static constexpr auto kModuleMaxAngularAcceleration =
wpi::math::pi * 2_rad_per_s / 1_s; // radians per second^2
frc::PWMVictorSPX m_driveMotor;
frc::PWMVictorSPX m_turningMotor;
frc::Encoder m_driveEncoder{0, 1};
frc::Encoder m_turningEncoder{2, 3};
frc2::PIDController m_drivePIDController{1.0, 0, 0};
frc::ProfiledPIDController<units::radians> m_turningPIDController{
1.0,
0.0,
0.0,
{kModuleMaxAngularVelocity, kModuleMaxAngularAcceleration}};
frc::SimpleMotorFeedforward<units::meters> m_driveFeedforward{1_V,
3_V / 1_mps};
frc::SimpleMotorFeedforward<units::radians> m_turnFeedforward{
1_V, 0.5_V / 1_rad_per_s};
};

View File

@@ -628,6 +628,38 @@
"mainclass": "Main",
"commandversion": 2
},
{
"name": "DifferentialDrivePoseEstimator",
"description": "Demonstrates the use of the DifferentialDrivePoseEstimator as a replacement for differential drive odometry.",
"tags": [
"Drivetrain",
"State space",
"Vision",
"Filter",
"Odometry",
"Pose"
],
"foldername": "DifferentialDrivePoseEstimator",
"gradlebase": "cpp",
"mainclass": "Main",
"commandversion": 2
},
{
"name": "MecanumDrivePoseEstimator",
"description": "Demonstrates the use of the MecanumDrivePoseEstimator as a replacement for mecanum odometry.",
"tags": [
"Drivetrain",
"State space",
"Vision",
"Filter",
"Odometry",
"Pose"
],
"foldername": "MecanumDrivePoseEstimator",
"gradlebase": "cpp",
"mainclass": "Main",
"commandversion": 2
},
{
"name": "ArmSimulation",
"description": "Demonstrates the use of physics simulation with a simple single-jointed arm.",
@@ -661,5 +693,22 @@
"gradlebase": "cpp",
"mainclass": "Main",
"commandversion": 2
},
{
"name": "SwerveDrivePoseEstimator",
"description": "Demonstrates the use of the SwerveDrivePoseEstimator as a replacement for mecanum drive odometry.",
"tags": [
"Drivetrain",
"State space",
"Vision",
"Filter",
"Odometry",
"State",
"Swerve"
],
"foldername": "SwerveDrivePoseEstimator",
"gradlebase": "cpp",
"mainclass": "Main",
"commandversion": 2
}
]