Fix C++ floating point literal formatting (#2114)

Found formatting errors with this regex
"([^a-z0-9\.]\.[0-9]|[^a-z0-9\.][0-9]\.[^a-z0-9\.])" and ignored false
positives.

Fixes #2112.
This commit is contained in:
Tyler Veness
2019-11-20 21:48:16 -08:00
committed by Peter Johnson
parent 3d1ca856b2
commit ffa4b907c0
40 changed files with 82 additions and 82 deletions

View File

@@ -35,7 +35,7 @@ void DriveSubsystem::ResetEncoders() {
}
double DriveSubsystem::GetAverageEncoderDistance() {
return (m_leftEncoder.GetDistance() + m_rightEncoder.GetDistance()) / 2.;
return (m_leftEncoder.GetDistance() + m_rightEncoder.GetDistance()) / 2.0;
}
frc::Encoder& DriveSubsystem::GetLeftEncoder() { return m_leftEncoder; }

View File

@@ -43,7 +43,7 @@ constexpr bool kEncoderReversed = false;
constexpr int kEncoderCPR = 1024;
constexpr double kEncoderDistancePerPulse =
// Distance units will be rotations
1. / static_cast<double>(kEncoderCPR);
1.0 / static_cast<double>(kEncoderCPR);
constexpr int kShooterMotorPort = 4;
constexpr int kFeederMotorPort = 5;
@@ -58,12 +58,12 @@ constexpr double kD = 0;
// On a real robot the feedforward constants should be empirically determined;
// these are reasonable guesses.
constexpr auto kS = .05_V;
constexpr auto kS = 0.05_V;
constexpr auto kV =
// Should have value 12V at free speed...
12_V / kShooterFreeRPS;
constexpr double kFeederSpeed = .5;
constexpr double kFeederSpeed = 0.5;
} // namespace ShooterConstants
namespace AutoConstants {

View File

@@ -90,7 +90,7 @@ class RobotContainer {
frc2::InstantCommand m_stopFeeder{[this] { m_shooter.StopFeeder(); },
{&m_shooter}};
frc2::InstantCommand m_driveHalfSpeed{[this] { m_drive.SetMaxOutput(.5); },
frc2::InstantCommand m_driveHalfSpeed{[this] { m_drive.SetMaxOutput(0.5); },
{}};
frc2::InstantCommand m_driveFullSpeed{[this] { m_drive.SetMaxOutput(1); },
{}};

View File

@@ -35,7 +35,7 @@ void DriveSubsystem::ResetEncoders() {
}
double DriveSubsystem::GetAverageEncoderDistance() {
return (m_leftEncoder.GetDistance() + m_rightEncoder.GetDistance()) / 2.;
return (m_leftEncoder.GetDistance() + m_rightEncoder.GetDistance()) / 2.0;
}
frc::Encoder& DriveSubsystem::GetLeftEncoder() { return m_leftEncoder; }
@@ -47,9 +47,9 @@ void DriveSubsystem::SetMaxOutput(double maxOutput) {
}
double DriveSubsystem::GetHeading() {
return std::remainder(m_gyro.GetAngle(), 360) * (kGyroReversed ? -1. : 1.);
return std::remainder(m_gyro.GetAngle(), 360) * (kGyroReversed ? -1.0 : 1.0);
}
double DriveSubsystem::GetTurnRate() {
return m_gyro.GetRate() * (kGyroReversed ? -1. : 1.);
return m_gyro.GetRate() * (kGyroReversed ? -1.0 : 1.0);
}

View File

@@ -38,7 +38,7 @@ constexpr double kEncoderDistancePerPulse =
constexpr bool kGyroReversed = true;
constexpr double kStabilizationP = 1;
constexpr double kStabilizationI = .5;
constexpr double kStabilizationI = 0.5;
constexpr double kStabilizationD = 0;
constexpr double kTurnP = 1;
@@ -52,7 +52,7 @@ constexpr double kTurnRateToleranceDegPerS = 10; // degrees per second
namespace AutoConstants {
constexpr double kAutoDriveDistanceInches = 60;
constexpr double kAutoBackupDistanceInches = 20;
constexpr double kAutoDriveSpeed = .5;
constexpr double kAutoDriveSpeed = 0.5;
} // namespace AutoConstants
namespace OIConstants {

View File

@@ -68,7 +68,7 @@ class RobotContainer {
// Require the robot drive
{&m_drive}};
frc2::InstantCommand m_driveHalfSpeed{[this] { m_drive.SetMaxOutput(.5); },
frc2::InstantCommand m_driveHalfSpeed{[this] { m_drive.SetMaxOutput(0.5); },
{}};
frc2::InstantCommand m_driveFullSpeed{[this] { m_drive.SetMaxOutput(1); },
{}};

View File

@@ -35,7 +35,7 @@ void DriveSubsystem::ResetEncoders() {
}
double DriveSubsystem::GetAverageEncoderDistance() {
return (m_leftEncoder.GetDistance() + m_rightEncoder.GetDistance()) / 2.;
return (m_leftEncoder.GetDistance() + m_rightEncoder.GetDistance()) / 2.0;
}
frc::Encoder& DriveSubsystem::GetLeftEncoder() { return m_leftEncoder; }

View File

@@ -44,7 +44,7 @@ constexpr int kHatchSolenoidPorts[]{0, 1};
namespace AutoConstants {
constexpr double kAutoDriveDistanceInches = 60;
constexpr double kAutoBackupDistanceInches = 20;
constexpr double kAutoDriveSpeed = .5;
constexpr double kAutoDriveSpeed = 0.5;
} // namespace AutoConstants
namespace OIConstants {

View File

@@ -63,7 +63,7 @@ class RobotContainer {
frc2::InstantCommand m_grabHatch{[this] { m_hatch.GrabHatch(); }, {&m_hatch}};
frc2::InstantCommand m_releaseHatch{[this] { m_hatch.ReleaseHatch(); },
{&m_hatch}};
frc2::InstantCommand m_driveHalfSpeed{[this] { m_drive.SetMaxOutput(.5); },
frc2::InstantCommand m_driveHalfSpeed{[this] { m_drive.SetMaxOutput(0.5); },
{}};
frc2::InstantCommand m_driveFullSpeed{[this] { m_drive.SetMaxOutput(1); },
{}};

View File

@@ -10,6 +10,6 @@
HalveDriveSpeed::HalveDriveSpeed(DriveSubsystem* subsystem)
: m_drive(subsystem) {}
void HalveDriveSpeed::Initialize() { m_drive->SetMaxOutput(.5); }
void HalveDriveSpeed::Initialize() { m_drive->SetMaxOutput(0.5); }
void HalveDriveSpeed::End(bool interrupted) { m_drive->SetMaxOutput(1); }

View File

@@ -35,7 +35,7 @@ void DriveSubsystem::ResetEncoders() {
}
double DriveSubsystem::GetAverageEncoderDistance() {
return (m_leftEncoder.GetDistance() + m_rightEncoder.GetDistance()) / 2.;
return (m_leftEncoder.GetDistance() + m_rightEncoder.GetDistance()) / 2.0;
}
frc::Encoder& DriveSubsystem::GetLeftEncoder() { return m_leftEncoder; }

View File

@@ -44,7 +44,7 @@ constexpr int kHatchSolenoidPorts[]{0, 1};
namespace AutoConstants {
constexpr double kAutoDriveDistanceInches = 60;
constexpr double kAutoBackupDistanceInches = 20;
constexpr double kAutoDriveSpeed = .5;
constexpr double kAutoDriveSpeed = 0.5;
} // namespace AutoConstants
namespace OIConstants {

View File

@@ -47,7 +47,7 @@ void DriveSubsystem::ResetEncoders() {
}
double DriveSubsystem::GetAverageEncoderDistance() {
return (m_leftEncoder.GetDistance() + m_rightEncoder.GetDistance()) / 2.;
return (m_leftEncoder.GetDistance() + m_rightEncoder.GetDistance()) / 2.0;
}
frc::Encoder& DriveSubsystem::GetLeftEncoder() { return m_leftEncoder; }
@@ -59,11 +59,11 @@ void DriveSubsystem::SetMaxOutput(double maxOutput) {
}
double DriveSubsystem::GetHeading() {
return std::remainder(m_gyro.GetAngle(), 360) * (kGyroReversed ? -1. : 1.);
return std::remainder(m_gyro.GetAngle(), 360) * (kGyroReversed ? -1.0 : 1.0);
}
double DriveSubsystem::GetTurnRate() {
return m_gyro.GetRate() * (kGyroReversed ? -1. : 1.);
return m_gyro.GetRate() * (kGyroReversed ? -1.0 : 1.0);
}
frc::Pose2d DriveSubsystem::GetPose() { return m_odometry.GetPose(); }

View File

@@ -32,7 +32,7 @@ constexpr int kRightEncoderPorts[]{2, 3};
constexpr bool kLeftEncoderReversed = false;
constexpr bool kRightEncoderReversed = true;
constexpr auto kTrackwidth = .6_m;
constexpr auto kTrackwidth = 0.6_m;
constexpr frc::DifferentialDriveKinematics kDriveKinematics(kTrackwidth);
constexpr int kEncoderCPR = 1024;
@@ -49,11 +49,11 @@ constexpr bool kGyroReversed = true;
// Toolsuite provides a convenient tool for obtaining these values for your
// robot.
constexpr auto ks = 1_V;
constexpr auto kv = .8 * 1_V * 1_s / 1_m;
constexpr auto ka = .15 * 1_V * 1_s * 1_s / 1_m;
constexpr auto kv = 0.8 * 1_V * 1_s / 1_m;
constexpr auto ka = 0.15 * 1_V * 1_s * 1_s / 1_m;
// Example value only - as above, this must be tuned for your drive!
constexpr double kPDriveVel = .5;
constexpr double kPDriveVel = 0.5;
} // namespace DriveConstants
namespace AutoConstants {
@@ -63,7 +63,7 @@ constexpr auto kMaxAcceleration = 3_mps_sq;
// Reasonable baseline values for a RAMSETE follower in units of meters and
// seconds
constexpr double kRamseteB = 2;
constexpr double kRamseteZeta = .7;
constexpr double kRamseteZeta = 0.7;
} // namespace AutoConstants
namespace OIConstants {

View File

@@ -41,7 +41,7 @@ class RobotContainer {
// The robot's subsystems
DriveSubsystem m_drive;
frc2::InstantCommand m_driveHalfSpeed{[this] { m_drive.SetMaxOutput(.5); },
frc2::InstantCommand m_driveHalfSpeed{[this] { m_drive.SetMaxOutput(0.5); },
{}};
frc2::InstantCommand m_driveFullSpeed{[this] { m_drive.SetMaxOutput(1); },
{}};