mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
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:
@@ -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); }, {}));
|
||||
}
|
||||
|
||||
@@ -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()});
|
||||
}
|
||||
|
||||
@@ -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);
|
||||
|
||||
@@ -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;
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -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;
|
||||
|
||||
Reference in New Issue
Block a user