Use stricter C++ type conversions (#4357)

Now, implicit narrowing conversions are only used with wpi::Now(). This
also fixes clang-tidy warnings about C-style casts. For example:
```
== clang-tidy /__w/allwpilib/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/SwerveControllerCommand.inc ==
/__w/allwpilib/allwpilib/wpilibNewCommands/src/main/native/include/frc2/command/SwerveControllerCommand.inc:95:18: warning: C-style casts are discouraged; use static_cast/const_cast/reinterpret_cast [google-readability-casting]
  auto curTime = units::second_t(m_timer.Get());
                 ^
```
In that case at least, the cast was removed entirely since Get() already
returns a units::second_t.
This commit is contained in:
Tyler Veness
2022-08-17 13:42:36 -07:00
committed by GitHub
parent 151dabb2af
commit ac9be78e27
139 changed files with 547 additions and 593 deletions

View File

@@ -26,9 +26,9 @@ void ArmSubsystem::UseOutput(double output, State setpoint) {
units::volt_t feedforward =
m_feedforward.Calculate(setpoint.position, setpoint.velocity);
// Add the feedforward to the PID output to get the motor output
m_motor.SetVoltage(units::volt_t(output) + feedforward);
m_motor.SetVoltage(units::volt_t{output} + feedforward);
}
units::radian_t ArmSubsystem::GetMeasurement() {
return units::radian_t(m_encoder.GetDistance()) + kArmOffset;
return units::radian_t{m_encoder.GetDistance()} + kArmOffset;
}

View File

@@ -120,8 +120,8 @@ class Robot : public frc::TimedRobot {
void TeleopInit() override {
// Read Preferences for Arm setpoint and kP on entering Teleop
armPosition = units::degree_t(
frc::Preferences::GetDouble(kArmPositionKey, armPosition.value()));
armPosition = units::degree_t{
frc::Preferences::GetDouble(kArmPositionKey, armPosition.value())};
if (kArmKp != frc::Preferences::GetDouble(kArmPKey, kArmKp)) {
kArmKp = frc::Preferences::GetDouble(kArmPKey, kArmKp);
m_controller.SetP(kArmKp);
@@ -133,8 +133,8 @@ class Robot : public frc::TimedRobot {
// Here, we run PID control like normal, with a setpoint read from
// preferences in degrees.
double pidOutput = m_controller.Calculate(
m_encoder.GetDistance(), (units::radian_t(armPosition).value()));
m_motor.SetVoltage(units::volt_t(pidOutput));
m_encoder.GetDistance(), (units::radian_t{armPosition}.value()));
m_motor.SetVoltage(units::volt_t{pidOutput});
} else {
// Otherwise, we disable the motor.
m_motor.Set(0.0);

View File

@@ -23,6 +23,6 @@ void Drivetrain::Drive(units::meters_per_second_t xSpeed,
void Drivetrain::UpdateOdometry() {
m_odometry.Update(m_gyro.GetRotation2d(),
units::meter_t(m_leftEncoder.GetDistance()),
units::meter_t(m_rightEncoder.GetDistance()));
units::meter_t{m_leftEncoder.GetDistance()},
units::meter_t{m_rightEncoder.GetDistance()});
}

View File

@@ -27,10 +27,10 @@ void Drivetrain::Drive(units::meters_per_second_t xSpeed,
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()));
{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

View File

@@ -78,8 +78,8 @@ class Drivetrain {
// Gains are for example purposes only - must be determined for your own
// robot!
frc::DifferentialDrivePoseEstimator m_poseEstimator{
frc::Rotation2d(),
frc::Pose2d(),
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}};

View File

@@ -16,9 +16,9 @@ class ExampleGlobalMeasurementSensor {
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)),
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(2))));
frc::Rotation2d{units::radian_t{randVec(2)}}};
}
};

View File

@@ -10,18 +10,18 @@ using namespace DriveConstants;
DriveDistanceProfiled::DriveDistanceProfiled(units::meter_t distance,
DriveSubsystem* drive)
: CommandHelper(
frc::TrapezoidProfile<units::meters>(
: CommandHelper{
frc::TrapezoidProfile<units::meters>{
// Limit the max acceleration and velocity
{kMaxSpeed, kMaxAcceleration},
// End at desired position in meters; implicitly starts at 0
{distance, 0_mps}),
{distance, 0_mps}},
// Pipe the profile state to the drive
[drive](auto setpointState) {
drive->SetDriveStates(setpointState, setpointState);
},
// Require the drive
{drive}) {
{drive}} {
// Reset drive encoders since we're starting at 0
drive->ResetEncoders();
}

View File

@@ -54,11 +54,11 @@ void DriveSubsystem::ResetEncoders() {
}
units::meter_t DriveSubsystem::GetLeftEncoderDistance() {
return units::meter_t(m_leftLeader.GetEncoderDistance());
return units::meter_t{m_leftLeader.GetEncoderDistance()};
}
units::meter_t DriveSubsystem::GetRightEncoderDistance() {
return units::meter_t(m_rightLeader.GetEncoderDistance());
return units::meter_t{m_rightLeader.GetEncoderDistance()};
}
void DriveSubsystem::SetMaxOutput(double maxOutput) {

View File

@@ -31,7 +31,7 @@ class Robot : public frc::TimedRobot {
// Run controller and update motor output
m_motor.Set(
m_controller.Calculate(units::meter_t(m_encoder.GetDistance())));
m_controller.Calculate(units::meter_t{m_encoder.GetDistance()}));
}
private:

View File

@@ -74,7 +74,7 @@ class Robot : public frc::TimedRobot {
m_mech2d.GetRoot("Elevator Root", 10, 0);
frc::MechanismLigament2d* m_elevatorMech2d =
m_elevatorRoot->Append<frc::MechanismLigament2d>(
"Elevator", units::inch_t(m_elevatorSim.GetPosition()).value(),
"Elevator", units::inch_t{m_elevatorSim.GetPosition()}.value(),
90_deg);
public:
@@ -103,15 +103,15 @@ class Robot : public frc::TimedRobot {
// Update the Elevator length based on the simulated elevator height
m_elevatorMech2d->SetLength(
units::inch_t(m_elevatorSim.GetPosition()).value());
units::inch_t{m_elevatorSim.GetPosition()}.value());
}
void TeleopPeriodic() override {
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(),
units::meter_t(30_in).value());
m_motor.SetVoltage(units::volt_t(pidOutput));
units::meter_t{30_in}.value());
m_motor.SetVoltage(units::volt_t{pidOutput});
} else {
// Otherwise, we disable the motor.
m_motor.Set(0.0);

View File

@@ -54,8 +54,8 @@ class Robot : public frc::TimedRobot {
// accelerate the shooter wheel
.IfHigh([&shooter = m_shooter, &controller = m_controller, &ff = m_ff,
&encoder = m_shooterEncoder] {
shooter.SetVoltage(units::volt_t(controller.Calculate(
encoder.GetRate(), SHOT_VELOCITY.value())) +
shooter.SetVoltage(units::volt_t{controller.Calculate(
encoder.GetRate(), SHOT_VELOCITY.value())} +
ff.Calculate(SHOT_VELOCITY));
});
// if not, stop

View File

@@ -11,7 +11,7 @@
using namespace ShooterConstants;
ShooterSubsystem::ShooterSubsystem()
: PIDSubsystem(frc2::PIDController(kP, kI, kD)),
: PIDSubsystem{frc2::PIDController{kP, kI, kD}},
m_shooterMotor(kShooterMotorPort),
m_feederMotor(kFeederMotorPort),
m_shooterEncoder(kEncoderPorts[0], kEncoderPorts[1]),
@@ -22,7 +22,7 @@ ShooterSubsystem::ShooterSubsystem()
}
void ShooterSubsystem::UseOutput(double output, double setpoint) {
m_shooterMotor.SetVoltage(units::volt_t(output) +
m_shooterMotor.SetVoltage(units::volt_t{output} +
m_shooterFeedforward.Calculate(kShooterTargetRPS));
}

View File

@@ -9,12 +9,13 @@
#include "Robot.h"
DriveStraight::DriveStraight(double distance, Drivetrain& drivetrain)
: frc2::CommandHelper<frc2::PIDCommand, DriveStraight>(
frc2::PIDController(4, 0, 0),
[&drivetrain] { return drivetrain.GetDistance(); }, distance,
: frc2::CommandHelper<frc2::PIDCommand, DriveStraight>{
frc2::PIDController{4, 0, 0},
[&drivetrain] { return drivetrain.GetDistance(); },
distance,
[&drivetrain](double output) { drivetrain.Drive(output, output); },
{&drivetrain}),
m_drivetrain(&drivetrain) {
{&drivetrain}},
m_drivetrain{&drivetrain} {
m_controller.SetTolerance(0.01);
}

View File

@@ -9,13 +9,13 @@
#include "Robot.h"
SetDistanceToBox::SetDistanceToBox(double distance, Drivetrain& drivetrain)
: frc2::CommandHelper<frc2::PIDCommand, SetDistanceToBox>(
frc2::PIDController(-2, 0, 0),
: frc2::CommandHelper<frc2::PIDCommand, SetDistanceToBox>{
frc2::PIDController{-2, 0, 0},
[&drivetrain] { return drivetrain.GetDistanceToObstacle(); },
distance,
[&drivetrain](double output) { drivetrain.Drive(output, output); },
{&drivetrain}),
m_drivetrain(&drivetrain) {
{&drivetrain}},
m_drivetrain{&drivetrain} {
m_controller.SetTolerance(0.01);
}

View File

@@ -9,7 +9,7 @@
#include <frc/smartdashboard/SmartDashboard.h>
Elevator::Elevator()
: frc2::PIDSubsystem(frc2::PIDController(kP_real, kI_real, 0)) {
: frc2::PIDSubsystem{frc2::PIDController{kP_real, kI_real, 0}} {
#ifdef SIMULATION // Check for simulation and update PID values
GetPIDController()->SetPID(kP_simulation, kI_simulation, 0, 0);
#endif

View File

@@ -7,7 +7,7 @@
#include <frc/controller/PIDController.h>
#include <frc/smartdashboard/SmartDashboard.h>
Wrist::Wrist() : frc2::PIDSubsystem(frc2::PIDController(kP, 0, 0)) {
Wrist::Wrist() : frc2::PIDSubsystem{frc2::PIDController{kP, 0, 0}} {
m_controller.SetTolerance(2.5);
SetName("Wrist");

View File

@@ -9,16 +9,15 @@
using namespace DriveConstants;
TurnToAngle::TurnToAngle(units::degree_t target, DriveSubsystem* drive)
: CommandHelper(
frc2::PIDController(kTurnP, kTurnI, kTurnD),
// Close loop on heading
[drive] { return drive->GetHeading().value(); },
// Set reference to target
target.value(),
// Pipe output to turn robot
[drive](double output) { drive->ArcadeDrive(0, output); },
// Require the drive
{drive}) {
: CommandHelper{frc2::PIDController{kTurnP, kTurnI, kTurnD},
// Close loop on heading
[drive] { return drive->GetHeading().value(); },
// Set reference to target
target.value(),
// Pipe output to turn robot
[drive](double output) { drive->ArcadeDrive(0, output); },
// Require the drive
{drive}} {
// Set the controller to be continuous (because it is an angle controller)
m_controller.EnableContinuousInput(-180, 180);
// Set the controller tolerance - the delta tolerance ensures the robot is

View File

@@ -10,9 +10,9 @@ using namespace DriveConstants;
TurnToAngleProfiled::TurnToAngleProfiled(units::degree_t target,
DriveSubsystem* drive)
: CommandHelper(
frc::ProfiledPIDController<units::radians>(
kTurnP, kTurnI, kTurnD, {kMaxTurnRate, kMaxTurnAcceleration}),
: CommandHelper{
frc::ProfiledPIDController<units::radians>{
kTurnP, kTurnI, kTurnD, {kMaxTurnRate, kMaxTurnAcceleration}},
// Close loop on heading
[drive] { return drive->GetHeading(); },
// Set reference to target
@@ -22,7 +22,7 @@ TurnToAngleProfiled::TurnToAngleProfiled(units::degree_t target,
drive->ArcadeDrive(0, output);
},
// Require the drive
{drive}) {
{drive}} {
// Set the controller to be continuous (because it is an angle controller)
GetController().EnableContinuousInput(-180_deg, 180_deg);
// Set the controller tolerance - the delta tolerance ensures the robot is

View File

@@ -53,8 +53,8 @@ void DriveSubsystem::SetMaxOutput(double maxOutput) {
}
units::degree_t DriveSubsystem::GetHeading() {
return units::degree_t(std::remainder(m_gyro.GetAngle(), 360) *
(kGyroReversed ? -1.0 : 1.0));
return units::degree_t{std::remainder(m_gyro.GetAngle(), 360) *
(kGyroReversed ? -1.0 : 1.0)};
}
double DriveSubsystem::GetTurnRate() {

View File

@@ -5,10 +5,10 @@
#include "Drivetrain.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())};
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) {

View File

@@ -7,10 +7,10 @@
namespace DriveConstants {
const frc::MecanumDriveKinematics kDriveKinematics{
frc::Translation2d(kWheelBase / 2, kTrackWidth / 2),
frc::Translation2d(kWheelBase / 2, -kTrackWidth / 2),
frc::Translation2d(-kWheelBase / 2, kTrackWidth / 2),
frc::Translation2d(-kWheelBase / 2, -kTrackWidth / 2)};
frc::Translation2d{kWheelBase / 2, kTrackWidth / 2},
frc::Translation2d{kWheelBase / 2, -kTrackWidth / 2},
frc::Translation2d{-kWheelBase / 2, kTrackWidth / 2},
frc::Translation2d{-kWheelBase / 2, -kTrackWidth / 2}};
} // namespace DriveConstants

View File

@@ -57,11 +57,11 @@ frc2::Command* RobotContainer::GetAutonomousCommand() {
// An example trajectory to follow. All units in meters.
auto exampleTrajectory = frc::TrajectoryGenerator::GenerateTrajectory(
// Start at the origin facing the +X direction
frc::Pose2d(0_m, 0_m, frc::Rotation2d(0_deg)),
frc::Pose2d{0_m, 0_m, 0_deg},
// Pass through these two interior waypoints, making an 's' curve path
{frc::Translation2d(1_m, 1_m), frc::Translation2d(2_m, -1_m)},
{frc::Translation2d{1_m, 1_m}, frc::Translation2d{2_m, -1_m}},
// End 3 meters straight ahead of where we started, facing forward
frc::Pose2d(3_m, 0_m, frc::Rotation2d(0_deg)),
frc::Pose2d{3_m, 0_m, 0_deg},
// Pass the config
config);
@@ -71,8 +71,8 @@ frc2::Command* RobotContainer::GetAutonomousCommand() {
frc::SimpleMotorFeedforward<units::meters>(ks, kv, ka),
DriveConstants::kDriveKinematics,
frc2::PIDController(AutoConstants::kPXController, 0, 0),
frc2::PIDController(AutoConstants::kPYController, 0, 0),
frc2::PIDController{AutoConstants::kPXController, 0, 0},
frc2::PIDController{AutoConstants::kPYController, 0, 0},
frc::ProfiledPIDController<units::radians>(
AutoConstants::kPThetaController, 0, 0,
AutoConstants::kThetaControllerConstraints),
@@ -81,18 +81,18 @@ frc2::Command* RobotContainer::GetAutonomousCommand() {
[this]() {
return frc::MecanumDriveWheelSpeeds{
units::meters_per_second_t(m_drive.GetFrontLeftEncoder().GetRate()),
units::meters_per_second_t(
m_drive.GetFrontRightEncoder().GetRate()),
units::meters_per_second_t(m_drive.GetRearLeftEncoder().GetRate()),
units::meters_per_second_t(
m_drive.GetRearRightEncoder().GetRate())};
units::meters_per_second_t{m_drive.GetFrontLeftEncoder().GetRate()},
units::meters_per_second_t{
m_drive.GetFrontRightEncoder().GetRate()},
units::meters_per_second_t{m_drive.GetRearLeftEncoder().GetRate()},
units::meters_per_second_t{
m_drive.GetRearRightEncoder().GetRate()}};
},
frc2::PIDController(DriveConstants::kPFrontLeftVel, 0, 0),
frc2::PIDController(DriveConstants::kPRearLeftVel, 0, 0),
frc2::PIDController(DriveConstants::kPFrontRightVel, 0, 0),
frc2::PIDController(DriveConstants::kPRearRightVel, 0, 0),
frc2::PIDController{DriveConstants::kPFrontLeftVel, 0, 0},
frc2::PIDController{DriveConstants::kPRearLeftVel, 0, 0},
frc2::PIDController{DriveConstants::kPFrontRightVel, 0, 0},
frc2::PIDController{DriveConstants::kPRearRightVel, 0, 0},
[this](units::volt_t frontLeft, units::volt_t rearLeft,
units::volt_t frontRight, units::volt_t rearRight) {

View File

@@ -28,7 +28,7 @@ DriveSubsystem::DriveSubsystem()
m_rearRightEncoder{kRearRightEncoderPorts[0], kRearRightEncoderPorts[1],
kRearRightEncoderReversed},
m_odometry{kDriveKinematics, m_gyro.GetRotation2d(), frc::Pose2d()} {
m_odometry{kDriveKinematics, m_gyro.GetRotation2d(), frc::Pose2d{}} {
// Set the distance per pulse for the encoders
m_frontLeftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
m_rearLeftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
@@ -46,10 +46,10 @@ void DriveSubsystem::Periodic() {
m_odometry.Update(
m_gyro.GetRotation2d(),
frc::MecanumDriveWheelSpeeds{
units::meters_per_second_t(m_frontLeftEncoder.GetRate()),
units::meters_per_second_t(m_rearLeftEncoder.GetRate()),
units::meters_per_second_t(m_frontRightEncoder.GetRate()),
units::meters_per_second_t(m_rearRightEncoder.GetRate())});
units::meters_per_second_t{m_frontLeftEncoder.GetRate()},
units::meters_per_second_t{m_rearLeftEncoder.GetRate()},
units::meters_per_second_t{m_frontRightEncoder.GetRate()},
units::meters_per_second_t{m_rearRightEncoder.GetRate()}});
}
void DriveSubsystem::Drive(double xSpeed, double ySpeed, double rot,
@@ -96,10 +96,10 @@ frc::Encoder& DriveSubsystem::GetRearRightEncoder() {
frc::MecanumDriveWheelSpeeds DriveSubsystem::getCurrentWheelSpeeds() {
return (frc::MecanumDriveWheelSpeeds{
units::meters_per_second_t(m_frontLeftEncoder.GetRate()),
units::meters_per_second_t(m_rearLeftEncoder.GetRate()),
units::meters_per_second_t(m_frontRightEncoder.GetRate()),
units::meters_per_second_t(m_rearRightEncoder.GetRate())});
units::meters_per_second_t{m_frontLeftEncoder.GetRate()},
units::meters_per_second_t{m_rearLeftEncoder.GetRate()},
units::meters_per_second_t{m_frontRightEncoder.GetRate()},
units::meters_per_second_t{m_rearRightEncoder.GetRate()}});
}
void DriveSubsystem::SetMaxOutput(double maxOutput) {

View File

@@ -7,6 +7,7 @@
#include <frc/trajectory/TrapezoidProfile.h>
#include <units/acceleration.h>
#include <units/angle.h>
#include <units/angular_acceleration.h>
#include <units/angular_velocity.h>
#include <units/length.h>
#include <units/time.h>
@@ -70,15 +71,10 @@ constexpr double kPRearRightVel = 0.5;
} // namespace DriveConstants
namespace AutoConstants {
using radians_per_second_squared_t =
units::compound_unit<units::radians,
units::inverse<units::squared<units::second>>>;
constexpr auto kMaxSpeed = units::meters_per_second_t(3);
constexpr auto kMaxAcceleration = units::meters_per_second_squared_t(3);
constexpr auto kMaxAngularSpeed = units::radians_per_second_t(3);
constexpr auto kMaxAngularAcceleration =
units::unit_t<radians_per_second_squared_t>(3);
constexpr auto kMaxSpeed = 3_mps;
constexpr auto kMaxAcceleration = 3_mps_sq;
constexpr auto kMaxAngularSpeed = 3_rad_per_s;
constexpr auto kMaxAngularAcceleration = 3_rad_per_s_sq;
constexpr double kPXController = 0.5;
constexpr double kPYController = 0.5;

View File

@@ -9,10 +9,10 @@
#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())};
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) {

View File

@@ -74,7 +74,7 @@ class Drivetrain {
// 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}};
frc::MecanumDrivePoseEstimator m_poseEstimator{0_deg, frc::Pose2d{},
m_kinematics, {0.1, 0.1, 0.1},
{0.05}, {0.1, 0.1, 0.1}};
};

View File

@@ -16,9 +16,9 @@ class ExampleGlobalMeasurementSensor {
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)),
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))));
frc::Rotation2d{units::radian_t{randVec(3)}}};
}
};

View File

@@ -41,7 +41,7 @@ class Robot : public frc::TimedRobot {
// update the dashboard mechanism's state
m_elevator->SetLength(kElevatorMinimumLength +
m_elevatorEncoder.GetDistance());
m_wrist->SetAngle(units::degree_t(m_wristPotentiometer.Get()));
m_wrist->SetAngle(units::degree_t{m_wristPotentiometer.Get()});
}
void TeleopPeriodic() override {

View File

@@ -38,21 +38,21 @@ void RobotContainer::ConfigureButtonBindings() {
// Configure your button bindings here
// While holding the shoulder button, drive at half speed
frc2::JoystickButton(&m_driverController, 6)
frc2::JoystickButton{&m_driverController, 6}
.WhenPressed(&m_driveHalfSpeed)
.WhenReleased(&m_driveFullSpeed);
}
frc2::Command* RobotContainer::GetAutonomousCommand() {
// Create a voltage constraint to ensure we don't accelerate too fast
frc::DifferentialDriveVoltageConstraint autoVoltageConstraint(
frc::SimpleMotorFeedforward<units::meters>(
DriveConstants::ks, DriveConstants::kv, DriveConstants::ka),
DriveConstants::kDriveKinematics, 10_V);
frc::DifferentialDriveVoltageConstraint autoVoltageConstraint{
frc::SimpleMotorFeedforward<units::meters>{
DriveConstants::ks, DriveConstants::kv, DriveConstants::ka},
DriveConstants::kDriveKinematics, 10_V};
// Set up config for trajectory
frc::TrajectoryConfig config(AutoConstants::kMaxSpeed,
AutoConstants::kMaxAcceleration);
frc::TrajectoryConfig config{AutoConstants::kMaxSpeed,
AutoConstants::kMaxAcceleration};
// Add kinematics to ensure max speed is actually obeyed
config.SetKinematics(DriveConstants::kDriveKinematics);
// Apply the voltage constraint
@@ -61,26 +61,27 @@ frc2::Command* RobotContainer::GetAutonomousCommand() {
// An example trajectory to follow. All units in meters.
auto exampleTrajectory = frc::TrajectoryGenerator::GenerateTrajectory(
// Start at the origin facing the +X direction
frc::Pose2d(0_m, 0_m, frc::Rotation2d(0_deg)),
frc::Pose2d{0_m, 0_m, 0_deg},
// Pass through these two interior waypoints, making an 's' curve path
{frc::Translation2d(1_m, 1_m), frc::Translation2d(2_m, -1_m)},
{frc::Translation2d{1_m, 1_m}, frc::Translation2d{2_m, -1_m}},
// End 3 meters straight ahead of where we started, facing forward
frc::Pose2d(3_m, 0_m, frc::Rotation2d(0_deg)),
frc::Pose2d{3_m, 0_m, 0_deg},
// Pass the config
config);
frc2::RamseteCommand ramseteCommand(
exampleTrajectory, [this]() { return m_drive.GetPose(); },
frc::RamseteController(AutoConstants::kRamseteB,
AutoConstants::kRamseteZeta),
frc::SimpleMotorFeedforward<units::meters>(
DriveConstants::ks, DriveConstants::kv, DriveConstants::ka),
frc2::RamseteCommand ramseteCommand{
exampleTrajectory,
[this]() { return m_drive.GetPose(); },
frc::RamseteController{AutoConstants::kRamseteB,
AutoConstants::kRamseteZeta},
frc::SimpleMotorFeedforward<units::meters>{
DriveConstants::ks, DriveConstants::kv, DriveConstants::ka},
DriveConstants::kDriveKinematics,
[this] { return m_drive.GetWheelSpeeds(); },
frc2::PIDController(DriveConstants::kPDriveVel, 0, 0),
frc2::PIDController(DriveConstants::kPDriveVel, 0, 0),
frc2::PIDController{DriveConstants::kPDriveVel, 0, 0},
frc2::PIDController{DriveConstants::kPDriveVel, 0, 0},
[this](auto left, auto right) { m_drive.TankDriveVolts(left, right); },
{&m_drive});
{&m_drive}};
// Reset odometry to the starting pose of the trajectory.
m_drive.ResetOdometry(exampleTrajectory.InitialPose());

View File

@@ -32,8 +32,8 @@ DriveSubsystem::DriveSubsystem()
void DriveSubsystem::Periodic() {
// Implementation of subsystem periodic method goes here.
m_odometry.Update(m_gyro.GetRotation2d(),
units::meter_t(m_leftEncoder.GetDistance()),
units::meter_t(m_rightEncoder.GetDistance()));
units::meter_t{m_leftEncoder.GetDistance()},
units::meter_t{m_rightEncoder.GetDistance()});
}
void DriveSubsystem::ArcadeDrive(double fwd, double rot) {
@@ -80,8 +80,8 @@ frc::Pose2d DriveSubsystem::GetPose() {
}
frc::DifferentialDriveWheelSpeeds DriveSubsystem::GetWheelSpeeds() {
return {units::meters_per_second_t(m_leftEncoder.GetRate()),
units::meters_per_second_t(m_rightEncoder.GetRate())};
return {units::meters_per_second_t{m_leftEncoder.GetRate()},
units::meters_per_second_t{m_rightEncoder.GetRate()}};
}
void DriveSubsystem::ResetOdometry(frc::Pose2d pose) {

View File

@@ -23,8 +23,8 @@ void Drivetrain::Drive(units::meters_per_second_t xSpeed,
void Drivetrain::UpdateOdometry() {
m_odometry.Update(m_gyro.GetRotation2d(),
units::meter_t(m_leftEncoder.GetDistance()),
units::meter_t(m_rightEncoder.GetDistance()));
units::meter_t{m_leftEncoder.GetDistance()},
units::meter_t{m_rightEncoder.GetDistance()});
}
void Drivetrain::ResetOdometry(const frc::Pose2d& pose) {

View File

@@ -79,9 +79,9 @@ class Robot : public frc::TimedRobot {
// An example trajectory to follow.
frc::Trajectory m_trajectory = frc::TrajectoryGenerator::GenerateTrajectory(
frc::Pose2d(0_m, 0_m, 0_rad),
{frc::Translation2d(1_m, 1_m), frc::Translation2d(2_m, -1_m)},
frc::Pose2d(3_m, 0_m, 0_rad), frc::TrajectoryConfig(3_fps, 3_fps_sq));
frc::Pose2d{0_m, 0_m, 0_rad},
{frc::Translation2d{1_m, 1_m}, frc::Translation2d{2_m, -1_m}},
frc::Pose2d{3_m, 0_m, 0_rad}, frc::TrajectoryConfig(3_fps, 3_fps_sq));
// The Ramsete Controller to follow the trajectory.
frc::RamseteController m_ramseteController;

View File

@@ -49,11 +49,11 @@ int Drivetrain::GetRightEncoderCount() {
}
units::meter_t Drivetrain::GetLeftDistance() {
return units::meter_t(m_leftEncoder.GetDistance());
return units::meter_t{m_leftEncoder.GetDistance()};
}
units::meter_t Drivetrain::GetRightDistance() {
return units::meter_t(m_rightEncoder.GetDistance());
return units::meter_t{m_rightEncoder.GetDistance()};
}
units::meter_t Drivetrain::GetAverageDistance() {

View File

@@ -25,8 +25,8 @@ void Drivetrain::Drive(units::meters_per_second_t xSpeed,
void Drivetrain::UpdateOdometry() {
m_odometry.Update(m_gyro.GetRotation2d(),
units::meter_t(m_leftEncoder.GetDistance()),
units::meter_t(m_rightEncoder.GetDistance()));
units::meter_t{m_leftEncoder.GetDistance()},
units::meter_t{m_rightEncoder.GetDistance()});
}
void Drivetrain::ResetOdometry(const frc::Pose2d& pose) {

View File

@@ -19,7 +19,7 @@ class Robot : public frc::TimedRobot {
SetNetworkTablesFlushEnabled(true);
m_trajectory = frc::TrajectoryGenerator::GenerateTrajectory(
frc::Pose2d(2_m, 2_m, 0_rad), {}, frc::Pose2d(6_m, 4_m, 0_rad),
frc::Pose2d{2_m, 2_m, 0_rad}, {}, frc::Pose2d{6_m, 4_m, 0_rad},
frc::TrajectoryConfig(2_mps, 2_mps_sq));
}

View File

@@ -100,8 +100,8 @@ class Robot : public frc::TimedRobot {
m_loop.Reset(frc::Vectord<2>{m_encoder.GetDistance(), m_encoder.GetRate()});
m_lastProfiledReference = {
units::radian_t(m_encoder.GetDistance()),
units::radians_per_second_t(m_encoder.GetRate())};
units::radian_t{m_encoder.GetDistance()},
units::radians_per_second_t{m_encoder.GetRate()}};
}
void TeleopPeriodic() override {
@@ -133,7 +133,7 @@ class Robot : public frc::TimedRobot {
// Send the new calculated voltage to the motors.
// voltage = duty cycle * battery voltage, so
// duty cycle = voltage / battery voltage
m_motor.SetVoltage(units::volt_t(m_loop.U(0)));
m_motor.SetVoltage(units::volt_t{m_loop.U(0)});
}
};

View File

@@ -75,24 +75,24 @@ frc2::Command* RobotContainer::GetAutonomousCommand() {
// An example trajectory to follow. All units in meters.
auto exampleTrajectory = frc::TrajectoryGenerator::GenerateTrajectory(
// Start at (1, 2) facing the +X direction
frc::Pose2d(1_m, 2_m, 0_deg),
frc::Pose2d{1_m, 2_m, 0_deg},
// Pass through these two interior waypoints, making an 's' curve path
{frc::Translation2d(2_m, 3_m), frc::Translation2d(3_m, 1_m)},
{frc::Translation2d{2_m, 3_m}, frc::Translation2d{3_m, 1_m}},
// End 3 meters straight ahead of where we started, facing forward
frc::Pose2d(4_m, 2_m, 0_deg),
frc::Pose2d{4_m, 2_m, 0_deg},
// Pass the config
config);
frc2::RamseteCommand ramseteCommand(
exampleTrajectory, [this] { return m_drive.GetPose(); },
frc::RamseteController(AutoConstants::kRamseteB,
AutoConstants::kRamseteZeta),
frc::RamseteController{AutoConstants::kRamseteB,
AutoConstants::kRamseteZeta},
frc::SimpleMotorFeedforward<units::meters>(
DriveConstants::ks, DriveConstants::kv, DriveConstants::ka),
DriveConstants::kDriveKinematics,
[this] { return m_drive.GetWheelSpeeds(); },
frc2::PIDController(DriveConstants::kPDriveVel, 0, 0),
frc2::PIDController(DriveConstants::kPDriveVel, 0, 0),
frc2::PIDController{DriveConstants::kPDriveVel, 0, 0},
frc2::PIDController{DriveConstants::kPDriveVel, 0, 0},
[this](auto left, auto right) { m_drive.TankDriveVolts(left, right); },
{&m_drive});

View File

@@ -30,8 +30,8 @@ DriveSubsystem::DriveSubsystem() {
void DriveSubsystem::Periodic() {
// Implementation of subsystem periodic method goes here.
m_odometry.Update(m_gyro.GetRotation2d(),
units::meter_t(m_leftEncoder.GetDistance()),
units::meter_t(m_rightEncoder.GetDistance()));
units::meter_t{m_leftEncoder.GetDistance()},
units::meter_t{m_rightEncoder.GetDistance()});
m_fieldSim.SetRobotPose(m_odometry.GetPose());
}
@@ -102,8 +102,8 @@ frc::Pose2d DriveSubsystem::GetPose() {
}
frc::DifferentialDriveWheelSpeeds DriveSubsystem::GetWheelSpeeds() {
return {units::meters_per_second_t(m_leftEncoder.GetRate()),
units::meters_per_second_t(m_rightEncoder.GetRate())};
return {units::meters_per_second_t{m_leftEncoder.GetRate()},
units::meters_per_second_t{m_rightEncoder.GetRate()}};
}
void DriveSubsystem::ResetOdometry(frc::Pose2d pose) {

View File

@@ -98,8 +98,8 @@ class Robot : public frc::TimedRobot {
// Reset our loop to make sure it's in a known state.
m_loop.Reset(frc::Vectord<2>{m_encoder.GetDistance(), m_encoder.GetRate()});
m_lastProfiledReference = {units::meter_t(m_encoder.GetDistance()),
units::meters_per_second_t(m_encoder.GetRate())};
m_lastProfiledReference = {units::meter_t{m_encoder.GetDistance()},
units::meters_per_second_t{m_encoder.GetRate()}};
}
void TeleopPeriodic() override {
@@ -131,7 +131,7 @@ class Robot : public frc::TimedRobot {
// Send the new calculated voltage to the motors.
// voltage = duty cycle * battery voltage, so
// duty cycle = voltage / battery voltage
m_motor.SetVoltage(units::volt_t(m_loop.U(0)));
m_motor.SetVoltage(units::volt_t{m_loop.U(0)});
}
};

View File

@@ -109,7 +109,7 @@ class Robot : public frc::TimedRobot {
// Send the new calculated voltage to the motors.
// voltage = duty cycle * battery voltage, so
// duty cycle = voltage / battery voltage
m_motor.SetVoltage(units::volt_t(m_loop.U(0)));
m_motor.SetVoltage(units::volt_t{m_loop.U(0)});
}
};

View File

@@ -109,7 +109,7 @@ class Robot : public frc::TimedRobot {
// Send the new calculated voltage to the motors.
// voltage = duty cycle * battery voltage, so
// duty cycle = voltage / battery voltage
m_motor.SetVoltage(units::volt_t(m_loop.U(0)));
m_motor.SetVoltage(units::volt_t{m_loop.U(0)});
}
};

View File

@@ -32,19 +32,19 @@ SwerveModule::SwerveModule(const int driveMotorChannel,
// 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::numbers::pi), units::radian_t(wpi::numbers::pi));
-units::radian_t{wpi::numbers::pi}, units::radian_t{wpi::numbers::pi});
}
frc::SwerveModuleState SwerveModule::GetState() const {
return {units::meters_per_second_t{m_driveEncoder.GetRate()},
frc::Rotation2d(units::radian_t(m_turningEncoder.Get()))};
units::radian_t{m_turningEncoder.GetDistance()}};
}
void SwerveModule::SetDesiredState(
const frc::SwerveModuleState& referenceState) {
// Optimize the reference state to avoid spinning further than 90 degrees
const auto state = frc::SwerveModuleState::Optimize(
referenceState, units::radian_t(m_turningEncoder.Get()));
referenceState, units::radian_t{m_turningEncoder.GetDistance()});
// Calculate the drive output from the drive PID controller.
const auto driveOutput = m_drivePIDController.Calculate(
@@ -54,7 +54,7 @@ void SwerveModule::SetDesiredState(
// 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());
units::radian_t{m_turningEncoder.GetDistance()}, state.angle.Radians());
const auto turnFeedforward = m_turnFeedforward.Calculate(
m_turningPIDController.GetSetpoint().velocity);

View File

@@ -35,9 +35,9 @@ RobotContainer::RobotContainer() {
m_drive.SetDefaultCommand(frc2::RunCommand(
[this] {
m_drive.Drive(
units::meters_per_second_t(m_driverController.GetLeftY()),
units::meters_per_second_t(m_driverController.GetLeftX()),
units::radians_per_second_t(m_driverController.GetRightX()), false);
units::meters_per_second_t{m_driverController.GetLeftY()},
units::meters_per_second_t{m_driverController.GetLeftX()},
units::radians_per_second_t{m_driverController.GetRightX()}, false);
},
{&m_drive}));
}
@@ -54,11 +54,11 @@ frc2::Command* RobotContainer::GetAutonomousCommand() {
// An example trajectory to follow. All units in meters.
auto exampleTrajectory = frc::TrajectoryGenerator::GenerateTrajectory(
// Start at the origin facing the +X direction
frc::Pose2d(0_m, 0_m, frc::Rotation2d(0_deg)),
frc::Pose2d{0_m, 0_m, 0_deg},
// Pass through these two interior waypoints, making an 's' curve path
{frc::Translation2d(1_m, 1_m), frc::Translation2d(2_m, -1_m)},
{frc::Translation2d{1_m, 1_m}, frc::Translation2d{2_m, -1_m}},
// End 3 meters straight ahead of where we started, facing forward
frc::Pose2d(3_m, 0_m, frc::Rotation2d(0_deg)),
frc::Pose2d{3_m, 0_m, 0_deg},
// Pass the config
config);
@@ -66,16 +66,16 @@ frc2::Command* RobotContainer::GetAutonomousCommand() {
AutoConstants::kPThetaController, 0, 0,
AutoConstants::kThetaControllerConstraints};
thetaController.EnableContinuousInput(units::radian_t(-wpi::numbers::pi),
units::radian_t(wpi::numbers::pi));
thetaController.EnableContinuousInput(units::radian_t{-wpi::numbers::pi},
units::radian_t{wpi::numbers::pi});
frc2::SwerveControllerCommand<4> swerveControllerCommand(
exampleTrajectory, [this]() { return m_drive.GetPose(); },
m_drive.kDriveKinematics,
frc2::PIDController(AutoConstants::kPXController, 0, 0),
frc2::PIDController(AutoConstants::kPYController, 0, 0), thetaController,
frc2::PIDController{AutoConstants::kPXController, 0, 0},
frc2::PIDController{AutoConstants::kPYController, 0, 0}, thetaController,
[this](auto moduleStates) { m_drive.SetModuleStates(moduleStates); },
@@ -88,10 +88,5 @@ frc2::Command* RobotContainer::GetAutonomousCommand() {
return new frc2::SequentialCommandGroup(
std::move(swerveControllerCommand),
frc2::InstantCommand(
[this]() {
m_drive.Drive(units::meters_per_second_t(0),
units::meters_per_second_t(0),
units::radians_per_second_t(0), false);
},
{}));
[this]() { m_drive.Drive(0_mps, 0_mps, 0_rad_per_s, false); }, {}));
}

View File

@@ -36,7 +36,7 @@ DriveSubsystem::DriveSubsystem()
kRearRightDriveEncoderPorts, kRearRightTurningEncoderPorts,
kRearRightDriveEncoderReversed, kRearRightTurningEncoderReversed},
m_odometry{kDriveKinematics, m_gyro.GetRotation2d(), frc::Pose2d()} {}
m_odometry{kDriveKinematics, m_gyro.GetRotation2d(), frc::Pose2d{}} {}
void DriveSubsystem::Periodic() {
// Implementation of subsystem periodic method goes here.
@@ -98,6 +98,5 @@ frc::Pose2d DriveSubsystem::GetPose() {
}
void DriveSubsystem::ResetOdometry(frc::Pose2d pose) {
m_odometry.ResetPosition(pose,
frc::Rotation2d(units::degree_t(GetHeading())));
m_odometry.ResetPosition(pose, units::degree_t{GetHeading()});
}

View File

@@ -35,19 +35,19 @@ SwerveModule::SwerveModule(int driveMotorChannel, int turningMotorChannel,
// 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::numbers::pi), units::radian_t(wpi::numbers::pi));
units::radian_t{-wpi::numbers::pi}, units::radian_t{wpi::numbers::pi});
}
frc::SwerveModuleState SwerveModule::GetState() {
return {units::meters_per_second_t{m_driveEncoder.GetRate()},
frc::Rotation2d(units::radian_t(m_turningEncoder.Get()))};
units::radian_t{m_turningEncoder.GetDistance()}};
}
void SwerveModule::SetDesiredState(
const frc::SwerveModuleState& referenceState) {
// Optimize the reference state to avoid spinning further than 90 degrees
const auto state = frc::SwerveModuleState::Optimize(
referenceState, units::radian_t(m_turningEncoder.Get()));
referenceState, units::radian_t{m_turningEncoder.GetDistance()});
// Calculate the drive output from the drive PID controller.
const auto driveOutput = m_drivePIDController.Calculate(
@@ -55,7 +55,7 @@ void SwerveModule::SetDesiredState(
// Calculate the turning motor output from the turning PID controller.
auto turnOutput = m_turningPIDController.Calculate(
units::radian_t(m_turningEncoder.Get()), state.angle.Radians());
units::radian_t{m_turningEncoder.GetDistance()}, state.angle.Radians());
// Set the motor outputs.
m_driveMotor.Set(driveOutput);

View File

@@ -7,6 +7,7 @@
#include <frc/trajectory/TrapezoidProfile.h>
#include <units/acceleration.h>
#include <units/angle.h>
#include <units/angular_acceleration.h>
#include <units/angular_velocity.h>
#include <units/length.h>
#include <units/time.h>
@@ -88,15 +89,10 @@ constexpr double kPModuleDriveController = 1;
} // namespace ModuleConstants
namespace AutoConstants {
using radians_per_second_squared_t =
units::compound_unit<units::radians,
units::inverse<units::squared<units::second>>>;
constexpr auto kMaxSpeed = units::meters_per_second_t(3);
constexpr auto kMaxAcceleration = units::meters_per_second_squared_t(3);
constexpr auto kMaxAngularSpeed = units::radians_per_second_t(3.142);
constexpr auto kMaxAngularAcceleration =
units::unit_t<radians_per_second_squared_t>(3.142);
constexpr auto kMaxSpeed = 3_mps;
constexpr auto kMaxAcceleration = 3_mps_sq;
constexpr auto kMaxAngularSpeed = 3.142_rad_per_s;
constexpr auto kMaxAngularAcceleration = 3.142_rad_per_s_sq;
constexpr double kPXController = 0.5;
constexpr double kPYController = 0.5;

View File

@@ -94,10 +94,10 @@ class DriveSubsystem : public frc2::SubsystemBase {
0.7_m; // Distance between centers of front and back wheels on robot
frc::SwerveDriveKinematics<4> kDriveKinematics{
frc::Translation2d(kWheelBase / 2, kTrackWidth / 2),
frc::Translation2d(kWheelBase / 2, -kTrackWidth / 2),
frc::Translation2d(-kWheelBase / 2, kTrackWidth / 2),
frc::Translation2d(-kWheelBase / 2, -kTrackWidth / 2)};
frc::Translation2d{kWheelBase / 2, kTrackWidth / 2},
frc::Translation2d{kWheelBase / 2, -kTrackWidth / 2},
frc::Translation2d{-kWheelBase / 2, kTrackWidth / 2},
frc::Translation2d{-kWheelBase / 2, -kTrackWidth / 2}};
private:
// Components (e.g. motor controllers and sensors) should generally be

View File

@@ -16,10 +16,6 @@
#include "Constants.h"
class SwerveModule {
using radians_per_second_squared_t =
units::compound_unit<units::radians,
units::inverse<units::squared<units::second>>>;
public:
SwerveModule(int driveMotorChannel, int turningMotorChannel,
const int driveEncoderPorts[2], const int turningEncoderPorts[2],
@@ -36,12 +32,10 @@ class SwerveModule {
// ProfiledPIDController's constraints only take in meters per second and
// meters per second squared.
static constexpr units::radians_per_second_t kModuleMaxAngularVelocity =
units::radians_per_second_t(wpi::numbers::pi); // radians per second
static constexpr units::unit_t<radians_per_second_squared_t>
kModuleMaxAngularAcceleration =
units::unit_t<radians_per_second_squared_t>(
wpi::numbers::pi * 2.0); // radians per second squared
static constexpr auto kModuleMaxAngularVelocity =
units::radians_per_second_t{wpi::numbers::pi};
static constexpr auto kModuleMaxAngularAcceleration =
units::radians_per_second_squared_t{wpi::numbers::pi * 2.0};
frc::Spark m_driveMotor;
frc::Spark m_turningMotor;

View File

@@ -32,19 +32,19 @@ SwerveModule::SwerveModule(const int driveMotorChannel,
// 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::numbers::pi), units::radian_t(wpi::numbers::pi));
-units::radian_t{wpi::numbers::pi}, units::radian_t{wpi::numbers::pi});
}
frc::SwerveModuleState SwerveModule::GetState() const {
return {units::meters_per_second_t{m_driveEncoder.GetRate()},
frc::Rotation2d(units::radian_t(m_turningEncoder.Get()))};
units::radian_t{m_turningEncoder.GetDistance()}};
}
void SwerveModule::SetDesiredState(
const frc::SwerveModuleState& referenceState) {
// Optimize the reference state to avoid spinning further than 90 degrees
const auto state = frc::SwerveModuleState::Optimize(
referenceState, units::radian_t(m_turningEncoder.Get()));
referenceState, units::radian_t{m_turningEncoder.GetDistance()});
// Calculate the drive output from the drive PID controller.
const auto driveOutput = m_drivePIDController.Calculate(
@@ -54,7 +54,7 @@ void SwerveModule::SetDesiredState(
// 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());
units::radian_t{m_turningEncoder.GetDistance()}, state.angle.Radians());
const auto turnFeedforward = m_turnFeedforward.Calculate(
m_turningPIDController.GetSetpoint().velocity);

View File

@@ -49,6 +49,6 @@ class Drivetrain {
// Gains are for example purposes only - must be determined for your own
// robot!
frc::SwerveDrivePoseEstimator<4> m_poseEstimator{
frc::Rotation2d(), frc::Pose2d(), m_kinematics,
frc::Rotation2d{}, frc::Pose2d{}, m_kinematics,
{0.1, 0.1, 0.1}, {0.05}, {0.1, 0.1, 0.1}};
};

View File

@@ -16,9 +16,9 @@ class ExampleGlobalMeasurementSensor {
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)),
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))));
frc::Rotation2d{units::radian_t{randVec(3)}}};
}
};