mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[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:
committed by
GitHub
parent
3413bfc06a
commit
bc8f338771
@@ -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);
|
||||
}
|
||||
@@ -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
|
||||
@@ -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);
|
||||
}
|
||||
@@ -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}};
|
||||
};
|
||||
@@ -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))));
|
||||
}
|
||||
};
|
||||
@@ -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};
|
||||
};
|
||||
Reference in New Issue
Block a user