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:
@@ -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});
|
||||
|
||||
|
||||
@@ -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) {
|
||||
|
||||
Reference in New Issue
Block a user