diff --git a/hal/lib/athena/AnalogGyro.cpp b/hal/lib/athena/AnalogGyro.cpp index 9032331506..eef7f49789 100644 --- a/hal/lib/athena/AnalogGyro.cpp +++ b/hal/lib/athena/AnalogGyro.cpp @@ -87,13 +87,13 @@ void HAL_SetupAnalogGyro(HAL_GyroHandle handle, int32_t* status) { if (*status != 0) return; HAL_SetAnalogOversampleBits(gyro->handle, kOversampleBits, status); if (*status != 0) return; - float sampleRate = + double sampleRate = kSamplesPerSecond * (1 << (kAverageBits + kOversampleBits)); HAL_SetAnalogSampleRate(sampleRate, status); if (*status != 0) return; Wait(0.1); - HAL_SetAnalogGyroDeadband(handle, 0.0f, status); + HAL_SetAnalogGyroDeadband(handle, 0.0, status); if (*status != 0) return; } diff --git a/hal/lib/athena/AnalogInput.cpp b/hal/lib/athena/AnalogInput.cpp index f2edba7b15..469932ff73 100644 --- a/hal/lib/athena/AnalogInput.cpp +++ b/hal/lib/athena/AnalogInput.cpp @@ -99,7 +99,7 @@ HAL_Bool HAL_CheckAnalogInputChannel(int32_t channel) { */ void HAL_SetAnalogSampleRate(double samplesPerSecond, int32_t* status) { // TODO: This will change when variable size scan lists are implemented. - // TODO: Need float comparison with epsilon. + // TODO: Need double comparison with epsilon. // wpi_assert(!sampleRateSet || GetSampleRate() == samplesPerSecond); initializeAnalog(status); if (*status != 0) return; diff --git a/hal/lib/athena/AnalogInternal.cpp b/hal/lib/athena/AnalogInternal.cpp index d4a0c3a8e1..daf523fb47 100644 --- a/hal/lib/athena/AnalogInternal.cpp +++ b/hal/lib/athena/AnalogInternal.cpp @@ -80,7 +80,7 @@ int32_t getAnalogNumChannelsToActivate(int32_t* status) { */ void setAnalogSampleRate(double samplesPerSecond, int32_t* status) { // TODO: This will change when variable size scan lists are implemented. - // TODO: Need float comparison with epsilon. + // TODO: Need double comparison with epsilon. // wpi_assert(!sampleRateSet || GetSampleRate() == samplesPerSecond); analogSampleRateSet = true; diff --git a/hal/lib/athena/DigitalInternal.h b/hal/lib/athena/DigitalInternal.h index 1b1544dd01..22c1035534 100644 --- a/hal/lib/athena/DigitalInternal.h +++ b/hal/lib/athena/DigitalInternal.h @@ -45,11 +45,11 @@ constexpr int32_t kExpectedLoopTiming = 40; * scaling is implemented as an output squelch to get longer periods for old * devices. */ -constexpr float kDefaultPwmPeriod = 5.05; +constexpr double kDefaultPwmPeriod = 5.05; /** * kDefaultPwmCenter is the PWM range center in ms */ -constexpr float kDefaultPwmCenter = 1.5; +constexpr double kDefaultPwmCenter = 1.5; /** * kDefaultPWMStepsDown is the number of PWM steps below the centerpoint */ diff --git a/hal/lib/athena/FRCDriverStation.cpp b/hal/lib/athena/FRCDriverStation.cpp index 87a7cb325a..acae7f51b9 100644 --- a/hal/lib/athena/FRCDriverStation.cpp +++ b/hal/lib/athena/FRCDriverStation.cpp @@ -100,16 +100,16 @@ int32_t HAL_GetJoystickAxes(int32_t joystickNum, HAL_JoystickAxes* axes) { joystickNum, reinterpret_cast(&axesInt), HAL_kMaxJoystickAxes); - // copy integer values to float values + // copy integer values to double values axes->count = axesInt.count; // current scaling is -128 to 127, can easily be patched in the future by // changing this function. for (int32_t i = 0; i < axesInt.count; i++) { int8_t value = axesInt.axes[i]; if (value < 0) { - axes->axes[i] = value / 128.0f; + axes->axes[i] = value / 128.0; } else { - axes->axes[i] = value / 127.0f; + axes->axes[i] = value / 127.0; } } diff --git a/wpilibc/athena/include/ADXRS450_Gyro.h b/wpilibc/athena/include/ADXRS450_Gyro.h index a68bb20d49..faef5533da 100644 --- a/wpilibc/athena/include/ADXRS450_Gyro.h +++ b/wpilibc/athena/include/ADXRS450_Gyro.h @@ -33,7 +33,7 @@ class ADXRS450_Gyro : public GyroBase { explicit ADXRS450_Gyro(SPI::Port port); virtual ~ADXRS450_Gyro() = default; - float GetAngle() const override; + double GetAngle() const override; double GetRate() const override; void Reset() override; void Calibrate() override; diff --git a/wpilibc/athena/include/AnalogAccelerometer.h b/wpilibc/athena/include/AnalogAccelerometer.h index 0771b71551..22cf2ea720 100644 --- a/wpilibc/athena/include/AnalogAccelerometer.h +++ b/wpilibc/athena/include/AnalogAccelerometer.h @@ -32,9 +32,9 @@ class AnalogAccelerometer : public SensorBase, explicit AnalogAccelerometer(std::shared_ptr channel); virtual ~AnalogAccelerometer() = default; - float GetAcceleration() const; - void SetSensitivity(float sensitivity); - void SetZero(float zero); + double GetAcceleration() const; + void SetSensitivity(double sensitivity); + void SetZero(double zero); double PIDGet() override; void UpdateTable() override; @@ -48,8 +48,8 @@ class AnalogAccelerometer : public SensorBase, void InitAccelerometer(); std::shared_ptr m_analogInput; - float m_voltsPerG = 1.0; - float m_zeroGVoltage = 2.5; + double m_voltsPerG = 1.0; + double m_zeroGVoltage = 2.5; std::shared_ptr m_table; }; diff --git a/wpilibc/athena/include/AnalogGyro.h b/wpilibc/athena/include/AnalogGyro.h index f97bbedd1a..739e3f5fdf 100644 --- a/wpilibc/athena/include/AnalogGyro.h +++ b/wpilibc/athena/include/AnalogGyro.h @@ -33,23 +33,23 @@ class AnalogGyro : public GyroBase { public: static const int kOversampleBits = 10; static const int kAverageBits = 0; - static constexpr float kSamplesPerSecond = 50.0; - static constexpr float kCalibrationSampleTime = 5.0; - static constexpr float kDefaultVoltsPerDegreePerSecond = 0.007; + static constexpr double kSamplesPerSecond = 50.0; + static constexpr double kCalibrationSampleTime = 5.0; + static constexpr double kDefaultVoltsPerDegreePerSecond = 0.007; explicit AnalogGyro(int channel); explicit AnalogGyro(AnalogInput* channel); explicit AnalogGyro(std::shared_ptr channel); - AnalogGyro(int channel, int center, float offset); - AnalogGyro(std::shared_ptr channel, int center, float offset); + AnalogGyro(int channel, int center, double offset); + AnalogGyro(std::shared_ptr channel, int center, double offset); virtual ~AnalogGyro(); - float GetAngle() const override; + double GetAngle() const override; double GetRate() const override; virtual int GetCenter() const; - virtual float GetOffset() const; - void SetSensitivity(float voltsPerDegreePerSecond); - void SetDeadband(float volts); + virtual double GetOffset() const; + void SetSensitivity(double voltsPerDegreePerSecond); + void SetDeadband(double volts); void Reset() override; virtual void InitGyro(); void Calibrate() override; diff --git a/wpilibc/athena/include/AnalogInput.h b/wpilibc/athena/include/AnalogInput.h index 2dc830aaac..614b6240ca 100644 --- a/wpilibc/athena/include/AnalogInput.h +++ b/wpilibc/athena/include/AnalogInput.h @@ -46,8 +46,8 @@ class AnalogInput : public SensorBase, int GetValue() const; int GetAverageValue() const; - float GetVoltage() const; - float GetAverageVoltage() const; + double GetVoltage() const; + double GetAverageVoltage() const; int GetChannel() const; @@ -69,8 +69,8 @@ class AnalogInput : public SensorBase, int64_t GetAccumulatorCount() const; void GetAccumulatorOutput(int64_t& value, int64_t& count) const; - static void SetSampleRate(float samplesPerSecond); - static float GetSampleRate(); + static void SetSampleRate(double samplesPerSecond); + static double GetSampleRate(); double PIDGet() override; diff --git a/wpilibc/athena/include/AnalogOutput.h b/wpilibc/athena/include/AnalogOutput.h index 04f10208dc..ef637d343b 100644 --- a/wpilibc/athena/include/AnalogOutput.h +++ b/wpilibc/athena/include/AnalogOutput.h @@ -26,8 +26,8 @@ class AnalogOutput : public SensorBase, public LiveWindowSendable { explicit AnalogOutput(int channel); virtual ~AnalogOutput(); - void SetVoltage(float voltage); - float GetVoltage() const; + void SetVoltage(double voltage); + double GetVoltage() const; void UpdateTable() override; void StartLiveWindowMode() override; diff --git a/wpilibc/athena/include/AnalogTrigger.h b/wpilibc/athena/include/AnalogTrigger.h index 535b4d0b1d..1c7345993c 100644 --- a/wpilibc/athena/include/AnalogTrigger.h +++ b/wpilibc/athena/include/AnalogTrigger.h @@ -25,7 +25,7 @@ class AnalogTrigger : public SensorBase { explicit AnalogTrigger(AnalogInput* channel); virtual ~AnalogTrigger(); - void SetLimitsVoltage(float lower, float upper); + void SetLimitsVoltage(double lower, double upper); void SetLimitsRaw(int lower, int upper); void SetAveraged(bool useAveragedValue); void SetFiltered(bool useFilteredValue); diff --git a/wpilibc/athena/include/CANSpeedController.h b/wpilibc/athena/include/CANSpeedController.h index c676f082d3..6be741bd97 100644 --- a/wpilibc/athena/include/CANSpeedController.h +++ b/wpilibc/athena/include/CANSpeedController.h @@ -63,8 +63,8 @@ class CANSpeedController : public SpeedController { kLimitMode_SrxDisableSwitchInputs = 2, }; - virtual float Get() const = 0; - virtual void Set(float value) = 0; + virtual double Get() const = 0; + virtual void Set(double value) = 0; virtual void StopMotor() = 0; virtual void Disable() = 0; virtual void SetP(double p) = 0; @@ -74,10 +74,10 @@ class CANSpeedController : public SpeedController { virtual double GetP() const = 0; virtual double GetI() const = 0; virtual double GetD() const = 0; - virtual float GetBusVoltage() const = 0; - virtual float GetOutputVoltage() const = 0; - virtual float GetOutputCurrent() const = 0; - virtual float GetTemperature() const = 0; + virtual double GetBusVoltage() const = 0; + virtual double GetOutputVoltage() const = 0; + virtual double GetOutputCurrent() const = 0; + virtual double GetTemperature() const = 0; virtual double GetPosition() const = 0; virtual double GetSpeed() const = 0; virtual bool GetForwardLimitOK() const = 0; @@ -95,7 +95,7 @@ class CANSpeedController : public SpeedController { virtual void ConfigForwardLimit(double forwardLimitPosition) = 0; virtual void ConfigReverseLimit(double reverseLimitPosition) = 0; virtual void ConfigMaxOutputVoltage(double voltage) = 0; - virtual void ConfigFaultTime(float faultTime) = 0; + virtual void ConfigFaultTime(double faultTime) = 0; // Hold off on interface until we figure out ControlMode enums. // virtual void SetControlMode(ControlMode mode) = 0; // virtual ControlMode GetControlMode() const = 0; diff --git a/wpilibc/athena/include/Compressor.h b/wpilibc/athena/include/Compressor.h index ffbc3200c0..bd77d6a436 100644 --- a/wpilibc/athena/include/Compressor.h +++ b/wpilibc/athena/include/Compressor.h @@ -34,7 +34,7 @@ class Compressor : public SensorBase, bool GetPressureSwitchValue() const; - float GetCompressorCurrent() const; + double GetCompressorCurrent() const; void SetClosedLoopControl(bool on); bool GetClosedLoopControl() const; diff --git a/wpilibc/athena/include/ControllerPower.h b/wpilibc/athena/include/ControllerPower.h index 52954aa80a..0e0bf7d2be 100644 --- a/wpilibc/athena/include/ControllerPower.h +++ b/wpilibc/athena/include/ControllerPower.h @@ -11,18 +11,18 @@ namespace frc { class ControllerPower { public: - static float GetInputVoltage(); - static float GetInputCurrent(); - static float GetVoltage3V3(); - static float GetCurrent3V3(); + static double GetInputVoltage(); + static double GetInputCurrent(); + static double GetVoltage3V3(); + static double GetCurrent3V3(); static bool GetEnabled3V3(); static int GetFaultCount3V3(); - static float GetVoltage5V(); - static float GetCurrent5V(); + static double GetVoltage5V(); + static double GetCurrent5V(); static bool GetEnabled5V(); static int GetFaultCount5V(); - static float GetVoltage6V(); - static float GetCurrent6V(); + static double GetVoltage6V(); + static double GetCurrent6V(); static bool GetEnabled6V(); static int GetFaultCount6V(); }; diff --git a/wpilibc/athena/include/Counter.h b/wpilibc/athena/include/Counter.h index 8e333f3646..b3c412052c 100644 --- a/wpilibc/athena/include/Counter.h +++ b/wpilibc/athena/include/Counter.h @@ -77,7 +77,7 @@ class Counter : public SensorBase, void SetUpDownCounterMode(); void SetExternalDirectionMode(); void SetSemiPeriodMode(bool highSemiPeriod); - void SetPulseLengthMode(float threshold); + void SetPulseLengthMode(double threshold); void SetReverseDirection(bool reverseDirection); diff --git a/wpilibc/athena/include/DigitalOutput.h b/wpilibc/athena/include/DigitalOutput.h index cc0dbc0bdc..c6adbd6bd0 100644 --- a/wpilibc/athena/include/DigitalOutput.h +++ b/wpilibc/athena/include/DigitalOutput.h @@ -32,12 +32,12 @@ class DigitalOutput : public DigitalSource, void Set(bool value); bool Get() const; int GetChannel() const override; - void Pulse(float length); + void Pulse(double length); bool IsPulsing() const; - void SetPWMRate(float rate); - void EnablePWM(float initialDutyCycle); + void SetPWMRate(double rate); + void EnablePWM(double initialDutyCycle); void DisablePWM(); - void UpdateDutyCycle(float dutyCycle); + void UpdateDutyCycle(double dutyCycle); // Digital Source Interface HAL_Handle GetPortHandleForRouting() const override; diff --git a/wpilibc/athena/include/DriverStation.h b/wpilibc/athena/include/DriverStation.h index 12bf58b5bd..820668da42 100644 --- a/wpilibc/athena/include/DriverStation.h +++ b/wpilibc/athena/include/DriverStation.h @@ -39,7 +39,7 @@ class DriverStation : public SensorBase, public RobotStateInterface { static const int kJoystickPorts = 6; - float GetStickAxis(int stick, int axis); + double GetStickAxis(int stick, int axis); int GetStickPOV(int stick, int pov); int GetStickButtons(int stick) const; bool GetStickButton(int stick, int button); @@ -69,7 +69,7 @@ class DriverStation : public SensorBase, public RobotStateInterface { void WaitForData(); bool WaitForData(double timeout); double GetMatchTime() const; - float GetBatteryVoltage() const; + double GetBatteryVoltage() const; /** Only to be used to tell the Driver Station what code you claim to be * executing for diagnostic purposes only diff --git a/wpilibc/athena/include/Encoder.h b/wpilibc/athena/include/Encoder.h index 8549e83494..645496dcfd 100644 --- a/wpilibc/athena/include/Encoder.h +++ b/wpilibc/athena/include/Encoder.h @@ -69,10 +69,10 @@ class Encoder : public SensorBase, bool GetStopped() const override; bool GetDirection() const override; - float GetDistance() const; - float GetRate() const; - void SetMinRate(float minRate); - void SetDistancePerPulse(float distancePerPulse); + double GetDistance() const; + double GetRate() const; + void SetMinRate(double minRate); + void SetDistancePerPulse(double distancePerPulse); void SetReverseDirection(bool reverseDirection); void SetSamplesToAverage(int samplesToAverage); int GetSamplesToAverage() const; @@ -97,7 +97,7 @@ class Encoder : public SensorBase, private: void InitEncoder(bool reverseDirection, EncodingType encodingType); - float DecodingScaleFactor() const; + double DecodingScaleFactor() const; std::shared_ptr m_aSource; // the A phase of the quad encoder std::shared_ptr m_bSource; // the B phase of the quad encoder diff --git a/wpilibc/athena/include/InterruptableSensorBase.h b/wpilibc/athena/include/InterruptableSensorBase.h index 079818d077..80b73e3d62 100644 --- a/wpilibc/athena/include/InterruptableSensorBase.h +++ b/wpilibc/athena/include/InterruptableSensorBase.h @@ -35,7 +35,7 @@ class InterruptableSensorBase : public SensorBase { virtual void CancelInterrupts(); ///< Free up the underlying chipobject functions. virtual WaitResult WaitForInterrupt( - float timeout, + double timeout, bool ignorePrevious = true); ///< Synchronus version. virtual void EnableInterrupts(); ///< Enable interrupts - after finishing setup. diff --git a/wpilibc/athena/include/MotorSafety.h b/wpilibc/athena/include/MotorSafety.h index 8b67ab50f9..1d6164b82c 100644 --- a/wpilibc/athena/include/MotorSafety.h +++ b/wpilibc/athena/include/MotorSafety.h @@ -15,8 +15,8 @@ namespace frc { class MotorSafety { public: - virtual void SetExpiration(float timeout) = 0; - virtual float GetExpiration() const = 0; + virtual void SetExpiration(double timeout) = 0; + virtual double GetExpiration() const = 0; virtual bool IsAlive() const = 0; virtual void StopMotor() = 0; virtual void SetSafetyEnabled(bool enabled) = 0; diff --git a/wpilibc/athena/include/MotorSafetyHelper.h b/wpilibc/athena/include/MotorSafetyHelper.h index fa5e809e04..00829e98da 100644 --- a/wpilibc/athena/include/MotorSafetyHelper.h +++ b/wpilibc/athena/include/MotorSafetyHelper.h @@ -21,8 +21,8 @@ class MotorSafetyHelper : public ErrorBase { explicit MotorSafetyHelper(MotorSafety* safeObject); ~MotorSafetyHelper(); void Feed(); - void SetExpiration(float expirationTime); - float GetExpiration() const; + void SetExpiration(double expirationTime); + double GetExpiration() const; bool IsAlive() const; void Check(); void SetSafetyEnabled(bool enabled); diff --git a/wpilibc/athena/include/PWM.h b/wpilibc/athena/include/PWM.h index d65e539b2d..a4ea48d890 100644 --- a/wpilibc/athena/include/PWM.h +++ b/wpilibc/athena/include/PWM.h @@ -48,16 +48,16 @@ class PWM : public SensorBase, virtual ~PWM(); virtual void SetRaw(uint16_t value); virtual uint16_t GetRaw() const; - virtual void SetPosition(float pos); - virtual float GetPosition() const; - virtual void SetSpeed(float speed); - virtual float GetSpeed() const; + virtual void SetPosition(double pos); + virtual double GetPosition() const; + virtual void SetSpeed(double speed); + virtual double GetSpeed() const; virtual void SetDisabled(); void SetPeriodMultiplier(PeriodMultiplier mult); void SetZeroLatch(); void EnableDeadbandElimination(bool eliminateDeadband); - void SetBounds(float max, float deadbandMax, float center, float deadbandMin, - float min); + void SetBounds(double max, double deadbandMax, double center, + double deadbandMin, double min); void SetRawBounds(int max, int deadbandMax, int center, int deadbandMin, int min); void GetRawBounds(int32_t* max, int32_t* deadbandMax, int32_t* center, diff --git a/wpilibc/athena/include/PWMSpeedController.h b/wpilibc/athena/include/PWMSpeedController.h index 3521027b5b..eff30b00f6 100644 --- a/wpilibc/athena/include/PWMSpeedController.h +++ b/wpilibc/athena/include/PWMSpeedController.h @@ -18,12 +18,12 @@ namespace frc { class PWMSpeedController : public SafePWM, public SpeedController { public: virtual ~PWMSpeedController() = default; - void Set(float value) override; - float Get() const override; + void Set(double value) override; + double Get() const override; void Disable() override; void StopMotor() override; - void PIDWrite(float output) override; + void PIDWrite(double output) override; void SetInverted(bool isInverted) override; bool GetInverted() const override; diff --git a/wpilibc/athena/include/PowerDistributionPanel.h b/wpilibc/athena/include/PowerDistributionPanel.h index 478177697a..1585ac2f9b 100644 --- a/wpilibc/athena/include/PowerDistributionPanel.h +++ b/wpilibc/athena/include/PowerDistributionPanel.h @@ -24,12 +24,12 @@ class PowerDistributionPanel : public SensorBase, public LiveWindowSendable { PowerDistributionPanel(); explicit PowerDistributionPanel(int module); - float GetVoltage() const; - float GetTemperature() const; - float GetCurrent(int channel) const; - float GetTotalCurrent() const; - float GetTotalPower() const; - float GetTotalEnergy() const; + double GetVoltage() const; + double GetTemperature() const; + double GetCurrent(int channel) const; + double GetTotalCurrent() const; + double GetTotalPower() const; + double GetTotalEnergy() const; void ResetTotalEnergy(); void ClearStickyFaults(); diff --git a/wpilibc/athena/include/Relay.h b/wpilibc/athena/include/Relay.h index 3b44695d83..68308a768c 100644 --- a/wpilibc/athena/include/Relay.h +++ b/wpilibc/athena/include/Relay.h @@ -47,8 +47,8 @@ class Relay : public MotorSafety, Value Get() const; int GetChannel() const; - void SetExpiration(float timeout) override; - float GetExpiration() const override; + void SetExpiration(double timeout) override; + double GetExpiration() const override; bool IsAlive() const override; void StopMotor() override; bool IsSafetyEnabled() const override; diff --git a/wpilibc/athena/include/RobotDrive.h b/wpilibc/athena/include/RobotDrive.h index 3044a41f04..9db5012442 100644 --- a/wpilibc/athena/include/RobotDrive.h +++ b/wpilibc/athena/include/RobotDrive.h @@ -58,7 +58,7 @@ class RobotDrive : public MotorSafety, public ErrorBase { RobotDrive(const RobotDrive&) = delete; RobotDrive& operator=(const RobotDrive&) = delete; - void Drive(float outputMagnitude, float curve); + void Drive(double outputMagnitude, double curve); void TankDrive(GenericHID* leftStick, GenericHID* rightStick, bool squaredInputs = true); void TankDrive(GenericHID& leftStick, GenericHID& rightStick, @@ -67,7 +67,8 @@ class RobotDrive : public MotorSafety, public ErrorBase { int rightAxis, bool squaredInputs = true); void TankDrive(GenericHID& leftStick, int leftAxis, GenericHID& rightStick, int rightAxis, bool squaredInputs = true); - void TankDrive(float leftValue, float rightValue, bool squaredInputs = true); + void TankDrive(double leftValue, double rightValue, + bool squaredInputs = true); void ArcadeDrive(GenericHID* stick, bool squaredInputs = true); void ArcadeDrive(GenericHID& stick, bool squaredInputs = true); void ArcadeDrive(GenericHID* moveStick, int moveChannel, @@ -76,19 +77,19 @@ class RobotDrive : public MotorSafety, public ErrorBase { void ArcadeDrive(GenericHID& moveStick, int moveChannel, GenericHID& rotateStick, int rotateChannel, bool squaredInputs = true); - void ArcadeDrive(float moveValue, float rotateValue, + void ArcadeDrive(double moveValue, double rotateValue, bool squaredInputs = true); - void MecanumDrive_Cartesian(float x, float y, float rotation, - float gyroAngle = 0.0); - void MecanumDrive_Polar(float magnitude, float direction, float rotation); - void HolonomicDrive(float magnitude, float direction, float rotation); - virtual void SetLeftRightMotorOutputs(float leftOutput, float rightOutput); + void MecanumDrive_Cartesian(double x, double y, double rotation, + double gyroAngle = 0.0); + void MecanumDrive_Polar(double magnitude, double direction, double rotation); + void HolonomicDrive(double magnitude, double direction, double rotation); + virtual void SetLeftRightMotorOutputs(double leftOutput, double rightOutput); void SetInvertedMotor(MotorType motor, bool isInverted); - void SetSensitivity(float sensitivity); + void SetSensitivity(double sensitivity); void SetMaxOutput(double maxOutput); - void SetExpiration(float timeout) override; - float GetExpiration() const override; + void SetExpiration(double timeout) override; + double GetExpiration() const override; bool IsAlive() const override; void StopMotor() override; bool IsSafetyEnabled() const override; @@ -97,12 +98,12 @@ class RobotDrive : public MotorSafety, public ErrorBase { protected: void InitRobotDrive(); - float Limit(float num); + double Limit(double num); void Normalize(double* wheelSpeeds); void RotateVector(double& x, double& y, double angle); static const int kMaxNumberOfMotors = 4; - float m_sensitivity = 0.5; + double m_sensitivity = 0.5; double m_maxOutput = 1.0; std::shared_ptr m_frontLeftMotor; std::shared_ptr m_frontRightMotor; diff --git a/wpilibc/athena/include/SafePWM.h b/wpilibc/athena/include/SafePWM.h index eb8ac472b2..a5eb3a4ba8 100644 --- a/wpilibc/athena/include/SafePWM.h +++ b/wpilibc/athena/include/SafePWM.h @@ -28,15 +28,15 @@ class SafePWM : public PWM, public MotorSafety { explicit SafePWM(int channel); virtual ~SafePWM() = default; - void SetExpiration(float timeout); - float GetExpiration() const; + void SetExpiration(double timeout); + double GetExpiration() const; bool IsAlive() const; void StopMotor(); bool IsSafetyEnabled() const; void SetSafetyEnabled(bool enabled); void GetDescription(std::ostringstream& desc) const; - virtual void SetSpeed(float speed); + virtual void SetSpeed(double speed); private: std::unique_ptr m_safetyHelper; diff --git a/wpilibc/athena/include/SerialPort.h b/wpilibc/athena/include/SerialPort.h index fea3a799fd..c9ddf969d0 100644 --- a/wpilibc/athena/include/SerialPort.h +++ b/wpilibc/athena/include/SerialPort.h @@ -61,7 +61,7 @@ class SerialPort : public ErrorBase { int GetBytesReceived(); int Read(char* buffer, int count); int Write(const std::string& buffer, int count); - void SetTimeout(float timeout); + void SetTimeout(double timeout); void SetReadBufferSize(int size); void SetWriteBufferSize(int size); void SetWriteBufferMode(WriteBufferMode mode); diff --git a/wpilibc/athena/include/Servo.h b/wpilibc/athena/include/Servo.h index d474dd3bd6..765601b485 100644 --- a/wpilibc/athena/include/Servo.h +++ b/wpilibc/athena/include/Servo.h @@ -26,13 +26,13 @@ class Servo : public SafePWM { public: explicit Servo(int channel); virtual ~Servo(); - void Set(float value); + void Set(double value); void SetOffline(); - float Get() const; - void SetAngle(float angle); - float GetAngle() const; - static float GetMaxAngle() { return kMaxServoAngle; } - static float GetMinAngle() { return kMinServoAngle; } + double Get() const; + void SetAngle(double angle); + double GetAngle() const; + static double GetMaxAngle() { return kMaxServoAngle; } + static double GetMinAngle() { return kMinServoAngle; } void ValueChanged(ITable* source, llvm::StringRef key, std::shared_ptr value, bool isNew) override; @@ -46,13 +46,13 @@ class Servo : public SafePWM { std::shared_ptr m_table; private: - float GetServoAngleRange() const { return kMaxServoAngle - kMinServoAngle; } + double GetServoAngleRange() const { return kMaxServoAngle - kMinServoAngle; } - static constexpr float kMaxServoAngle = 180.0; - static constexpr float kMinServoAngle = 0.0; + static constexpr double kMaxServoAngle = 180.0; + static constexpr double kMinServoAngle = 0.0; - static constexpr float kDefaultMaxServoPWM = 2.4; - static constexpr float kDefaultMinServoPWM = .6; + static constexpr double kDefaultMaxServoPWM = 2.4; + static constexpr double kDefaultMinServoPWM = .6; }; } // namespace frc diff --git a/wpilibc/athena/include/SpeedController.h b/wpilibc/athena/include/SpeedController.h index e518f649e8..0ca0bd480a 100644 --- a/wpilibc/athena/include/SpeedController.h +++ b/wpilibc/athena/include/SpeedController.h @@ -22,14 +22,14 @@ class SpeedController : public PIDOutput { * * @param speed The speed to set. Value should be between -1.0 and 1.0. */ - virtual void Set(float speed) = 0; + virtual void Set(double speed) = 0; /** * Common interface for getting the current set speed of a speed controller. * * @return The current set speed. Value is between -1.0 and 1.0. */ - virtual float Get() const = 0; + virtual double Get() const = 0; /** * Common interface for inverting direction of a speed controller. diff --git a/wpilibc/athena/src/ADXRS450_Gyro.cpp b/wpilibc/athena/src/ADXRS450_Gyro.cpp index 8ae165427e..a1c878988b 100644 --- a/wpilibc/athena/src/ADXRS450_Gyro.cpp +++ b/wpilibc/athena/src/ADXRS450_Gyro.cpp @@ -137,9 +137,8 @@ void ADXRS450_Gyro::Reset() { m_spi.ResetAccumulator(); } * @return the current heading of the robot in degrees. This heading is based on * integration of the returned rate from the gyro. */ -float ADXRS450_Gyro::GetAngle() const { - return static_cast(m_spi.GetAccumulatorValue() * - kDegreePerSecondPerLSB * kSamplePeriod); +double ADXRS450_Gyro::GetAngle() const { + return m_spi.GetAccumulatorValue() * kDegreePerSecondPerLSB * kSamplePeriod; } /** diff --git a/wpilibc/athena/src/AnalogAccelerometer.cpp b/wpilibc/athena/src/AnalogAccelerometer.cpp index ae746ef701..21614a87ba 100644 --- a/wpilibc/athena/src/AnalogAccelerometer.cpp +++ b/wpilibc/athena/src/AnalogAccelerometer.cpp @@ -81,7 +81,7 @@ AnalogAccelerometer::AnalogAccelerometer(std::shared_ptr channel) * * @return The current acceleration of the sensor in Gs. */ -float AnalogAccelerometer::GetAcceleration() const { +double AnalogAccelerometer::GetAcceleration() const { return (m_analogInput->GetAverageVoltage() - m_zeroGVoltage) / m_voltsPerG; } @@ -94,7 +94,7 @@ float AnalogAccelerometer::GetAcceleration() const { * * @param sensitivity The sensitivity of accelerometer in Volts per G. */ -void AnalogAccelerometer::SetSensitivity(float sensitivity) { +void AnalogAccelerometer::SetSensitivity(double sensitivity) { m_voltsPerG = sensitivity; } @@ -106,7 +106,7 @@ void AnalogAccelerometer::SetSensitivity(float sensitivity) { * * @param zero The zero G voltage. */ -void AnalogAccelerometer::SetZero(float zero) { m_zeroGVoltage = zero; } +void AnalogAccelerometer::SetZero(double zero) { m_zeroGVoltage = zero; } /** * Get the Acceleration for the PID Source parent. diff --git a/wpilibc/athena/src/AnalogGyro.cpp b/wpilibc/athena/src/AnalogGyro.cpp index a5e521ebc6..336479a479 100644 --- a/wpilibc/athena/src/AnalogGyro.cpp +++ b/wpilibc/athena/src/AnalogGyro.cpp @@ -19,9 +19,9 @@ using namespace frc; const int AnalogGyro::kOversampleBits; const int AnalogGyro::kAverageBits; -constexpr float AnalogGyro::kSamplesPerSecond; -constexpr float AnalogGyro::kCalibrationSampleTime; -constexpr float AnalogGyro::kDefaultVoltsPerDegreePerSecond; +constexpr double AnalogGyro::kSamplesPerSecond; +constexpr double AnalogGyro::kCalibrationSampleTime; +constexpr double AnalogGyro::kDefaultVoltsPerDegreePerSecond; /** * Gyro constructor using the Analog Input channel number. @@ -78,7 +78,7 @@ AnalogGyro::AnalogGyro(std::shared_ptr channel) * value. * @param offset Preset uncalibrated value to use as the gyro offset. */ -AnalogGyro::AnalogGyro(int channel, int center, float offset) { +AnalogGyro::AnalogGyro(int channel, int center, double offset) { m_analog = std::make_shared(channel); InitGyro(); int32_t status = 0; @@ -104,7 +104,7 @@ AnalogGyro::AnalogGyro(int channel, int center, float offset) { * connected to. */ AnalogGyro::AnalogGyro(std::shared_ptr channel, int center, - float offset) + double offset) : m_analog(channel) { if (channel == nullptr) { wpi_setWPIError(NullParameter); @@ -198,10 +198,10 @@ void AnalogGyro::Calibrate() { * @return the current heading of the robot in degrees. This heading is based on * integration of the returned rate from the gyro. */ -float AnalogGyro::GetAngle() const { - if (StatusIsFatal()) return 0.f; +double AnalogGyro::GetAngle() const { + if (StatusIsFatal()) return 0.0; int32_t status = 0; - float value = HAL_GetAnalogGyroAngle(m_gyroHandle, &status); + double value = HAL_GetAnalogGyroAngle(m_gyroHandle, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); return value; } @@ -227,10 +227,10 @@ double AnalogGyro::GetRate() const { * * @return the current offset value */ -float AnalogGyro::GetOffset() const { +double AnalogGyro::GetOffset() const { if (StatusIsFatal()) return 0.0; int32_t status = 0; - float value = HAL_GetAnalogGyroOffset(m_gyroHandle, &status); + double value = HAL_GetAnalogGyroOffset(m_gyroHandle, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); return value; } @@ -258,7 +258,7 @@ int AnalogGyro::GetCenter() const { * * @param voltsPerDegreePerSecond The sensitivity in Volts/degree/second */ -void AnalogGyro::SetSensitivity(float voltsPerDegreePerSecond) { +void AnalogGyro::SetSensitivity(double voltsPerDegreePerSecond) { int32_t status = 0; HAL_SetAnalogGyroVoltsPerDegreePerSecond(m_gyroHandle, voltsPerDegreePerSecond, &status); @@ -274,7 +274,7 @@ void AnalogGyro::SetSensitivity(float voltsPerDegreePerSecond) { * * @param volts The size of the deadband in volts */ -void AnalogGyro::SetDeadband(float volts) { +void AnalogGyro::SetDeadband(double volts) { if (StatusIsFatal()) return; int32_t status = 0; HAL_SetAnalogGyroDeadband(m_gyroHandle, volts, &status); diff --git a/wpilibc/athena/src/AnalogInput.cpp b/wpilibc/athena/src/AnalogInput.cpp index 0803b8aef3..ae3e4dd585 100644 --- a/wpilibc/athena/src/AnalogInput.cpp +++ b/wpilibc/athena/src/AnalogInput.cpp @@ -107,10 +107,10 @@ int AnalogInput::GetAverageValue() const { * * @return A scaled sample straight from this channel. */ -float AnalogInput::GetVoltage() const { - if (StatusIsFatal()) return 0.0f; +double AnalogInput::GetVoltage() const { + if (StatusIsFatal()) return 0.0; int32_t status = 0; - float voltage = HAL_GetAnalogVoltage(m_port, &status); + double voltage = HAL_GetAnalogVoltage(m_port, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); return voltage; } @@ -129,10 +129,10 @@ float AnalogInput::GetVoltage() const { * @return A scaled sample from the output of the oversample and average engine * for this channel. */ -float AnalogInput::GetAverageVoltage() const { - if (StatusIsFatal()) return 0.0f; +double AnalogInput::GetAverageVoltage() const { + if (StatusIsFatal()) return 0.0; int32_t status = 0; - float voltage = HAL_GetAnalogAverageVoltage(m_port, &status); + double voltage = HAL_GetAnalogAverageVoltage(m_port, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); return voltage; } @@ -293,9 +293,9 @@ void AnalogInput::ResetAccumulator() { if (!StatusIsFatal()) { // Wait until the next sample, so the next call to GetAccumulator*() // won't have old values. - const float sampleTime = 1.0f / GetSampleRate(); - const float overSamples = 1 << GetOversampleBits(); - const float averageSamples = 1 << GetAverageBits(); + const double sampleTime = 1.0 / GetSampleRate(); + const double overSamples = 1 << GetOversampleBits(); + const double averageSamples = 1 << GetAverageBits(); Wait(sampleTime * overSamples * averageSamples); } } @@ -385,7 +385,7 @@ void AnalogInput::GetAccumulatorOutput(int64_t& value, int64_t& count) const { * * @param samplesPerSecond The number of samples per second. */ -void AnalogInput::SetSampleRate(float samplesPerSecond) { +void AnalogInput::SetSampleRate(double samplesPerSecond) { int32_t status = 0; HAL_SetAnalogSampleRate(samplesPerSecond, &status); wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status)); @@ -396,9 +396,9 @@ void AnalogInput::SetSampleRate(float samplesPerSecond) { * * @return Sample rate. */ -float AnalogInput::GetSampleRate() { +double AnalogInput::GetSampleRate() { int32_t status = 0; - float sampleRate = HAL_GetAnalogSampleRate(&status); + double sampleRate = HAL_GetAnalogSampleRate(&status); wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status)); return sampleRate; } diff --git a/wpilibc/athena/src/AnalogOutput.cpp b/wpilibc/athena/src/AnalogOutput.cpp index 6382b348b3..1ea9b0b752 100644 --- a/wpilibc/athena/src/AnalogOutput.cpp +++ b/wpilibc/athena/src/AnalogOutput.cpp @@ -63,7 +63,7 @@ AnalogOutput::~AnalogOutput() { HAL_FreeAnalogOutputPort(m_port); } * * @param voltage The output value in Volts, from 0.0 to +5.0 */ -void AnalogOutput::SetVoltage(float voltage) { +void AnalogOutput::SetVoltage(double voltage) { int32_t status = 0; HAL_SetAnalogOutput(m_port, voltage, &status); @@ -75,9 +75,9 @@ void AnalogOutput::SetVoltage(float voltage) { * * @return The value in Volts, from 0.0 to +5.0 */ -float AnalogOutput::GetVoltage() const { +double AnalogOutput::GetVoltage() const { int32_t status = 0; - float voltage = HAL_GetAnalogOutput(m_port, &status); + double voltage = HAL_GetAnalogOutput(m_port, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); diff --git a/wpilibc/athena/src/AnalogTrigger.cpp b/wpilibc/athena/src/AnalogTrigger.cpp index 1c55e9433a..2fc0bb3a2f 100644 --- a/wpilibc/athena/src/AnalogTrigger.cpp +++ b/wpilibc/athena/src/AnalogTrigger.cpp @@ -83,7 +83,7 @@ void AnalogTrigger::SetLimitsRaw(int lower, int upper) { * @param lower The lower limit of the trigger in Volts. * @param upper The upper limit of the trigger in Volts. */ -void AnalogTrigger::SetLimitsVoltage(float lower, float upper) { +void AnalogTrigger::SetLimitsVoltage(double lower, double upper) { if (StatusIsFatal()) return; int32_t status = 0; HAL_SetAnalogTriggerLimitsVoltage(m_trigger, lower, upper, &status); diff --git a/wpilibc/athena/src/Compressor.cpp b/wpilibc/athena/src/Compressor.cpp index e54391fdb0..e1101bcf9e 100644 --- a/wpilibc/athena/src/Compressor.cpp +++ b/wpilibc/athena/src/Compressor.cpp @@ -89,10 +89,10 @@ bool Compressor::GetPressureSwitchValue() const { * * @return The current through the compressor, in amps */ -float Compressor::GetCompressorCurrent() const { +double Compressor::GetCompressorCurrent() const { if (StatusIsFatal()) return 0; int32_t status = 0; - float value; + double value; value = HAL_GetCompressorCurrent(m_compressorHandle, &status); diff --git a/wpilibc/athena/src/ControllerPower.cpp b/wpilibc/athena/src/ControllerPower.cpp index 857611d03e..86f2e98f79 100644 --- a/wpilibc/athena/src/ControllerPower.cpp +++ b/wpilibc/athena/src/ControllerPower.cpp @@ -20,9 +20,9 @@ using namespace frc; * * @return The controller input voltage value in Volts */ -float ControllerPower::GetInputVoltage() { +double ControllerPower::GetInputVoltage() { int32_t status = 0; - float retVal = HAL_GetVinVoltage(&status); + double retVal = HAL_GetVinVoltage(&status); wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status)); return retVal; } @@ -32,9 +32,9 @@ float ControllerPower::GetInputVoltage() { * * @return The controller input current value in Amps */ -float ControllerPower::GetInputCurrent() { +double ControllerPower::GetInputCurrent() { int32_t status = 0; - float retVal = HAL_GetVinCurrent(&status); + double retVal = HAL_GetVinCurrent(&status); wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status)); return retVal; } @@ -44,9 +44,9 @@ float ControllerPower::GetInputCurrent() { * * @return The controller 6V rail voltage value in Volts */ -float ControllerPower::GetVoltage6V() { +double ControllerPower::GetVoltage6V() { int32_t status = 0; - float retVal = HAL_GetUserVoltage6V(&status); + double retVal = HAL_GetUserVoltage6V(&status); wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status)); return retVal; } @@ -56,9 +56,9 @@ float ControllerPower::GetVoltage6V() { * * @return The controller 6V rail output current value in Amps */ -float ControllerPower::GetCurrent6V() { +double ControllerPower::GetCurrent6V() { int32_t status = 0; - float retVal = HAL_GetUserCurrent6V(&status); + double retVal = HAL_GetUserCurrent6V(&status); wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status)); return retVal; } @@ -94,9 +94,9 @@ int ControllerPower::GetFaultCount6V() { * * @return The controller 5V rail voltage value in Volts */ -float ControllerPower::GetVoltage5V() { +double ControllerPower::GetVoltage5V() { int32_t status = 0; - float retVal = HAL_GetUserVoltage5V(&status); + double retVal = HAL_GetUserVoltage5V(&status); wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status)); return retVal; } @@ -106,9 +106,9 @@ float ControllerPower::GetVoltage5V() { * * @return The controller 5V rail output current value in Amps */ -float ControllerPower::GetCurrent5V() { +double ControllerPower::GetCurrent5V() { int32_t status = 0; - float retVal = HAL_GetUserCurrent5V(&status); + double retVal = HAL_GetUserCurrent5V(&status); wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status)); return retVal; } @@ -144,9 +144,9 @@ int ControllerPower::GetFaultCount5V() { * * @return The controller 3.3V rail voltage value in Volts */ -float ControllerPower::GetVoltage3V3() { +double ControllerPower::GetVoltage3V3() { int32_t status = 0; - float retVal = HAL_GetUserVoltage3V3(&status); + double retVal = HAL_GetUserVoltage3V3(&status); wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status)); return retVal; } @@ -156,9 +156,9 @@ float ControllerPower::GetVoltage3V3() { * * @return The controller 3.3V rail output current value in Amps */ -float ControllerPower::GetCurrent3V3() { +double ControllerPower::GetCurrent3V3() { int32_t status = 0; - float retVal = HAL_GetUserCurrent3V3(&status); + double retVal = HAL_GetUserCurrent3V3(&status); wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status)); return retVal; } diff --git a/wpilibc/athena/src/Counter.cpp b/wpilibc/athena/src/Counter.cpp index ffb8220177..ae562a11c8 100644 --- a/wpilibc/athena/src/Counter.cpp +++ b/wpilibc/athena/src/Counter.cpp @@ -446,7 +446,7 @@ void Counter::SetSemiPeriodMode(bool highSemiPeriod) { * @param threshold The pulse length beyond which the counter counts the * opposite direction. Units are seconds. */ -void Counter::SetPulseLengthMode(float threshold) { +void Counter::SetPulseLengthMode(double threshold) { if (StatusIsFatal()) return; int32_t status = 0; HAL_SetCounterPulseLengthMode(m_counter, threshold, &status); diff --git a/wpilibc/athena/src/DigitalOutput.cpp b/wpilibc/athena/src/DigitalOutput.cpp index df26d3e06f..362fe931f1 100644 --- a/wpilibc/athena/src/DigitalOutput.cpp +++ b/wpilibc/athena/src/DigitalOutput.cpp @@ -102,7 +102,7 @@ int DigitalOutput::GetChannel() const { return m_channel; } * * @param length The pulselength in seconds */ -void DigitalOutput::Pulse(float length) { +void DigitalOutput::Pulse(double length) { if (StatusIsFatal()) return; int32_t status = 0; @@ -134,7 +134,7 @@ bool DigitalOutput::IsPulsing() const { * * @param rate The frequency to output all digital output PWM signals. */ -void DigitalOutput::SetPWMRate(float rate) { +void DigitalOutput::SetPWMRate(double rate) { if (StatusIsFatal()) return; int32_t status = 0; @@ -155,7 +155,7 @@ void DigitalOutput::SetPWMRate(float rate) { * * @param initialDutyCycle The duty-cycle to start generating. [0..1] */ -void DigitalOutput::EnablePWM(float initialDutyCycle) { +void DigitalOutput::EnablePWM(double initialDutyCycle) { if (m_pwmGenerator != HAL_kInvalidHandle) return; int32_t status = 0; @@ -202,7 +202,7 @@ void DigitalOutput::DisablePWM() { * * @param dutyCycle The duty-cycle to change to. [0..1] */ -void DigitalOutput::UpdateDutyCycle(float dutyCycle) { +void DigitalOutput::UpdateDutyCycle(double dutyCycle) { if (StatusIsFatal()) return; int32_t status = 0; diff --git a/wpilibc/athena/src/DriverStation.cpp b/wpilibc/athena/src/DriverStation.cpp index 5d2916e920..cd7318709d 100644 --- a/wpilibc/athena/src/DriverStation.cpp +++ b/wpilibc/athena/src/DriverStation.cpp @@ -79,7 +79,7 @@ void DriverStation::ReportError(bool is_error, int32_t code, * @param axis The analog axis value to read from the joystick. * @return The value of the axis on the joystick. */ -float DriverStation::GetStickAxis(int stick, int axis) { +double DriverStation::GetStickAxis(int stick, int axis) { if (stick >= kJoystickPorts) { wpi_setWPIError(BadJoystickIndex); return 0; @@ -94,7 +94,7 @@ float DriverStation::GetStickAxis(int stick, int axis) { else ReportJoystickUnpluggedWarning( "Joystick Axis missing, check if all controllers are plugged in"); - return 0.0f; + return 0.0; } return m_joystickAxes[stick].axes[axis]; @@ -518,9 +518,9 @@ double DriverStation::GetMatchTime() const { * * @return The battery voltage in Volts. */ -float DriverStation::GetBatteryVoltage() const { +double DriverStation::GetBatteryVoltage() const { int32_t status = 0; - float voltage = HAL_GetVinVoltage(&status); + double voltage = HAL_GetVinVoltage(&status); wpi_setErrorWithContext(status, "getVinVoltage"); return voltage; diff --git a/wpilibc/athena/src/Encoder.cpp b/wpilibc/athena/src/Encoder.cpp index c6a2dbdb2b..69e7c378a9 100644 --- a/wpilibc/athena/src/Encoder.cpp +++ b/wpilibc/athena/src/Encoder.cpp @@ -296,10 +296,10 @@ bool Encoder::GetDirection() const { * The scale needed to convert a raw counter value into a number of encoder * pulses. */ -float Encoder::DecodingScaleFactor() const { +double Encoder::DecodingScaleFactor() const { if (StatusIsFatal()) return 0.0; int32_t status = 0; - float val = HAL_GetEncoderDecodingScaleFactor(m_encoder, &status); + double val = HAL_GetEncoderDecodingScaleFactor(m_encoder, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); return val; } @@ -310,10 +310,10 @@ float Encoder::DecodingScaleFactor() const { * @return The distance driven since the last reset as scaled by the value from * SetDistancePerPulse(). */ -float Encoder::GetDistance() const { +double Encoder::GetDistance() const { if (StatusIsFatal()) return 0.0; int32_t status = 0; - float value = HAL_GetEncoderDistance(m_encoder, &status); + double value = HAL_GetEncoderDistance(m_encoder, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); return value; } @@ -326,10 +326,10 @@ float Encoder::GetDistance() const { * * @return The current rate of the encoder. */ -float Encoder::GetRate() const { +double Encoder::GetRate() const { if (StatusIsFatal()) return 0.0; int32_t status = 0; - float value = HAL_GetEncoderRate(m_encoder, &status); + double value = HAL_GetEncoderRate(m_encoder, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); return value; } @@ -340,7 +340,7 @@ float Encoder::GetRate() const { * @param minRate The minimum rate. The units are in distance per second as * scaled by the value from SetDistancePerPulse(). */ -void Encoder::SetMinRate(float minRate) { +void Encoder::SetMinRate(double minRate) { if (StatusIsFatal()) return; int32_t status = 0; HAL_SetEncoderMinRate(m_encoder, minRate, &status); @@ -364,7 +364,7 @@ void Encoder::SetMinRate(float minRate) { * @param distancePerPulse The scale factor that will be used to convert pulses * to useful units. */ -void Encoder::SetDistancePerPulse(float distancePerPulse) { +void Encoder::SetDistancePerPulse(double distancePerPulse) { if (StatusIsFatal()) return; int32_t status = 0; HAL_SetEncoderDistancePerPulse(m_encoder, distancePerPulse, &status); diff --git a/wpilibc/athena/src/GenericHID.cpp b/wpilibc/athena/src/GenericHID.cpp index 9d4656963d..4b4986080a 100644 --- a/wpilibc/athena/src/GenericHID.cpp +++ b/wpilibc/athena/src/GenericHID.cpp @@ -22,7 +22,7 @@ GenericHID::GenericHID(int port) : m_ds(DriverStation::GetInstance()) { * @param axis The axis to read, starting at 0. * @return The value of the axis. */ -float GenericHID::GetRawAxis(int axis) const { +double GenericHID::GetRawAxis(int axis) const { return m_ds.GetStickAxis(m_port, axis); } diff --git a/wpilibc/athena/src/InterruptableSensorBase.cpp b/wpilibc/athena/src/InterruptableSensorBase.cpp index 5998248dba..2fc0fac633 100644 --- a/wpilibc/athena/src/InterruptableSensorBase.cpp +++ b/wpilibc/athena/src/InterruptableSensorBase.cpp @@ -99,7 +99,7 @@ void InterruptableSensorBase::CancelInterrupts() { * @return What interrupts fired */ InterruptableSensorBase::WaitResult InterruptableSensorBase::WaitForInterrupt( - float timeout, bool ignorePrevious) { + double timeout, bool ignorePrevious) { if (StatusIsFatal()) return InterruptableSensorBase::kTimeout; wpi_assert(m_interrupt != HAL_kInvalidHandle); int32_t status = 0; diff --git a/wpilibc/athena/src/Joystick.cpp b/wpilibc/athena/src/Joystick.cpp index d20c8be350..3456e5e208 100644 --- a/wpilibc/athena/src/Joystick.cpp +++ b/wpilibc/athena/src/Joystick.cpp @@ -90,7 +90,7 @@ Joystick* Joystick::GetStickForPort(int port) { * @param hand This parameter is ignored for the Joystick class and is only * here to complete the GenericHID interface. */ -float Joystick::GetX(JoystickHand hand) const { +double Joystick::GetX(JoystickHand hand) const { return GetRawAxis(m_axes[kXAxis]); } @@ -102,7 +102,7 @@ float Joystick::GetX(JoystickHand hand) const { * @param hand This parameter is ignored for the Joystick class and is only * here to complete the GenericHID interface. */ -float Joystick::GetY(JoystickHand hand) const { +double Joystick::GetY(JoystickHand hand) const { return GetRawAxis(m_axes[kYAxis]); } @@ -111,7 +111,7 @@ float Joystick::GetY(JoystickHand hand) const { * * This depends on the mapping of the joystick connected to the current port. */ -float Joystick::GetZ(JoystickHand hand) const { +double Joystick::GetZ(JoystickHand hand) const { return GetRawAxis(m_axes[kZAxis]); } @@ -120,14 +120,14 @@ float Joystick::GetZ(JoystickHand hand) const { * * This depends on the mapping of the joystick connected to the current port. */ -float Joystick::GetTwist() const { return GetRawAxis(m_axes[kTwistAxis]); } +double Joystick::GetTwist() const { return GetRawAxis(m_axes[kTwistAxis]); } /** * Get the throttle value of the current joystick. * * This depends on the mapping of the joystick connected to the current port. */ -float Joystick::GetThrottle() const { +double Joystick::GetThrottle() const { return GetRawAxis(m_axes[kThrottleAxis]); } @@ -141,7 +141,7 @@ float Joystick::GetThrottle() const { * @param axis The axis to read. * @return The value of the axis. */ -float Joystick::GetAxis(AxisType axis) const { +double Joystick::GetAxis(AxisType axis) const { switch (axis) { case kXAxis: return this->GetX(); @@ -253,7 +253,7 @@ void Joystick::SetAxisChannel(AxisType axis, int channel) { * * @return The magnitude of the direction vector */ -float Joystick::GetMagnitude() const { +double Joystick::GetMagnitude() const { return std::sqrt(std::pow(GetX(), 2) + std::pow(GetY(), 2)); } @@ -263,7 +263,7 @@ float Joystick::GetMagnitude() const { * * @return The direction of the vector in radians */ -float Joystick::GetDirectionRadians() const { +double Joystick::GetDirectionRadians() const { return std::atan2(GetX(), -GetY()); } @@ -276,6 +276,6 @@ float Joystick::GetDirectionRadians() const { * * @return The direction of the vector in degrees */ -float Joystick::GetDirectionDegrees() const { +double Joystick::GetDirectionDegrees() const { return (180 / std::acos(-1)) * GetDirectionRadians(); } diff --git a/wpilibc/athena/src/MotorSafetyHelper.cpp b/wpilibc/athena/src/MotorSafetyHelper.cpp index 8a1353aff3..bf2893cfcf 100644 --- a/wpilibc/athena/src/MotorSafetyHelper.cpp +++ b/wpilibc/athena/src/MotorSafetyHelper.cpp @@ -59,7 +59,7 @@ void MotorSafetyHelper::Feed() { * Set the expiration time for the corresponding motor safety object. * @param expirationTime The timeout value in seconds. */ -void MotorSafetyHelper::SetExpiration(float expirationTime) { +void MotorSafetyHelper::SetExpiration(double expirationTime) { std::lock_guard sync(m_syncMutex); m_expiration = expirationTime; } @@ -68,7 +68,7 @@ void MotorSafetyHelper::SetExpiration(float expirationTime) { * Retrieve the timeout value for the corresponding motor safety object. * @return the timeout value in seconds. */ -float MotorSafetyHelper::GetExpiration() const { +double MotorSafetyHelper::GetExpiration() const { std::lock_guard sync(m_syncMutex); return m_expiration; } diff --git a/wpilibc/athena/src/PIDController.cpp b/wpilibc/athena/src/PIDController.cpp index 946a765201..5410eab102 100644 --- a/wpilibc/athena/src/PIDController.cpp +++ b/wpilibc/athena/src/PIDController.cpp @@ -36,9 +36,9 @@ static const std::string kEnabled = "enabled"; * effects calculations of the integral and differental terms. * The default is 50ms. */ -PIDController::PIDController(float Kp, float Ki, float Kd, PIDSource* source, - PIDOutput* output, float period) - : PIDController(Kp, Ki, Kd, 0.0f, source, output, period) {} +PIDController::PIDController(double Kp, double Ki, double Kd, PIDSource* source, + PIDOutput* output, double period) + : PIDController(Kp, Ki, Kd, 0.0, source, output, period) {} /** * Allocate a PID object with the given constants for P, I, D. @@ -52,9 +52,9 @@ PIDController::PIDController(float Kp, float Ki, float Kd, PIDSource* source, * effects calculations of the integral and differental terms. * The default is 50ms. */ -PIDController::PIDController(float Kp, float Ki, float Kd, float Kf, +PIDController::PIDController(double Kp, double Ki, double Kd, double Kf, PIDSource* source, PIDOutput* output, - float period) { + double period) { m_controlLoop = std::make_unique(&PIDController::Calculate, this); m_P = Kp; @@ -101,8 +101,8 @@ void PIDController::Calculate() { if (enabled) { std::lock_guard sync(m_mutex); - float input = pidInput->PIDGet(); - float result; + double input = pidInput->PIDGet(); + double result; PIDOutput* pidOutput; m_error = GetContinuousError(m_setpoint - input); @@ -284,7 +284,7 @@ double PIDController::GetF() const { * * @return the latest calculated output */ -float PIDController::Get() const { +double PIDController::Get() const { std::lock_guard sync(m_mutex); return m_result; } @@ -309,7 +309,7 @@ void PIDController::SetContinuous(bool continuous) { * @param minimumInput the minimum value expected from the input * @param maximumInput the maximum value expected from the output */ -void PIDController::SetInputRange(float minimumInput, float maximumInput) { +void PIDController::SetInputRange(double minimumInput, double maximumInput) { { std::lock_guard sync(m_mutex); m_minimumInput = minimumInput; @@ -325,7 +325,7 @@ void PIDController::SetInputRange(float minimumInput, float maximumInput) { * @param minimumOutput the minimum value to write to the output * @param maximumOutput the maximum value to write to the output */ -void PIDController::SetOutputRange(float minimumOutput, float maximumOutput) { +void PIDController::SetOutputRange(double minimumOutput, double maximumOutput) { std::lock_guard sync(m_mutex); m_minimumOutput = minimumOutput; m_maximumOutput = maximumOutput; @@ -338,7 +338,7 @@ void PIDController::SetOutputRange(float minimumOutput, float maximumOutput) { * * @param setpoint the desired setpoint */ -void PIDController::SetSetpoint(float setpoint) { +void PIDController::SetSetpoint(double setpoint) { { std::lock_guard sync(m_mutex); @@ -388,7 +388,7 @@ double PIDController::GetDeltaSetpoint() const { * * @return the current error */ -float PIDController::GetError() const { +double PIDController::GetError() const { double setpoint = GetSetpoint(); { std::lock_guard sync(m_mutex); @@ -419,8 +419,8 @@ PIDSourceType PIDController::GetPIDSourceType() const { * * @return the average error */ -float PIDController::GetAvgError() const { - float avgError = 0; +double PIDController::GetAvgError() const { + double avgError = 0; { std::lock_guard sync(m_mutex); // Don't divide by zero. @@ -435,7 +435,7 @@ float PIDController::GetAvgError() const { * * @param percentage error which is tolerable */ -void PIDController::SetTolerance(float percent) { +void PIDController::SetTolerance(double percent) { std::lock_guard sync(m_mutex); m_toleranceType = kPercentTolerance; m_tolerance = percent; @@ -447,7 +447,7 @@ void PIDController::SetTolerance(float percent) { * * @param percentage error which is tolerable */ -void PIDController::SetAbsoluteTolerance(float absTolerance) { +void PIDController::SetAbsoluteTolerance(double absTolerance) { std::lock_guard sync(m_mutex); m_toleranceType = kAbsoluteTolerance; m_tolerance = absTolerance; @@ -459,7 +459,7 @@ void PIDController::SetAbsoluteTolerance(float absTolerance) { * * @param percentage error which is tolerable */ -void PIDController::SetPercentTolerance(float percent) { +void PIDController::SetPercentTolerance(double percent) { std::lock_guard sync(m_mutex); m_toleranceType = kPercentTolerance; m_tolerance = percent; diff --git a/wpilibc/athena/src/PWM.cpp b/wpilibc/athena/src/PWM.cpp index a6d2212767..c08f3af947 100644 --- a/wpilibc/athena/src/PWM.cpp +++ b/wpilibc/athena/src/PWM.cpp @@ -100,8 +100,8 @@ void PWM::EnableDeadbandElimination(bool eliminateDeadband) { * @param deadbandMin The low end of the deadband pulse width in ms * @param min The minimum pulse width in ms */ -void PWM::SetBounds(float max, float deadbandMax, float center, - float deadbandMin, float min) { +void PWM::SetBounds(double max, double deadbandMax, double center, + double deadbandMin, double min) { if (StatusIsFatal()) return; int32_t status = 0; HAL_SetPWMConfig(m_handle, max, deadbandMax, center, deadbandMin, min, @@ -162,7 +162,7 @@ void PWM::GetRawBounds(int* max, int* deadbandMax, int* center, * * @param pos The position to set the servo between 0.0 and 1.0. */ -void PWM::SetPosition(float pos) { +void PWM::SetPosition(double pos) { if (StatusIsFatal()) return; int32_t status = 0; HAL_SetPWMPosition(m_handle, pos, &status); @@ -179,10 +179,10 @@ void PWM::SetPosition(float pos) { * * @return The position the servo is set to between 0.0 and 1.0. */ -float PWM::GetPosition() const { +double PWM::GetPosition() const { if (StatusIsFatal()) return 0.0; int32_t status = 0; - float position = HAL_GetPWMPosition(m_handle, &status); + double position = HAL_GetPWMPosition(m_handle, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); return position; } @@ -200,7 +200,7 @@ float PWM::GetPosition() const { * * @param speed The speed to set the speed controller between -1.0 and 1.0. */ -void PWM::SetSpeed(float speed) { +void PWM::SetSpeed(double speed) { if (StatusIsFatal()) return; int32_t status = 0; HAL_SetPWMSpeed(m_handle, speed, &status); @@ -219,10 +219,10 @@ void PWM::SetSpeed(float speed) { * * @return The most recently set speed between -1.0 and 1.0. */ -float PWM::GetSpeed() const { +double PWM::GetSpeed() const { if (StatusIsFatal()) return 0.0; int32_t status = 0; - float speed = HAL_GetPWMSpeed(m_handle, &status); + double speed = HAL_GetPWMSpeed(m_handle, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); return speed; } diff --git a/wpilibc/athena/src/PWMSpeedController.cpp b/wpilibc/athena/src/PWMSpeedController.cpp index 2d59883701..2c572393da 100644 --- a/wpilibc/athena/src/PWMSpeedController.cpp +++ b/wpilibc/athena/src/PWMSpeedController.cpp @@ -25,7 +25,7 @@ PWMSpeedController::PWMSpeedController(int channel) : SafePWM(channel) {} * * @param speed The speed value between -1.0 and 1.0 to set. */ -void PWMSpeedController::Set(float speed) { +void PWMSpeedController::Set(double speed) { SetSpeed(m_isInverted ? -speed : speed); } @@ -34,7 +34,7 @@ void PWMSpeedController::Set(float speed) { * * @return The most recently set value for the PWM between -1.0 and 1.0. */ -float PWMSpeedController::Get() const { return GetSpeed(); } +double PWMSpeedController::Get() const { return GetSpeed(); } /** * Common interface for disabling a motor. @@ -63,7 +63,7 @@ bool PWMSpeedController::GetInverted() const { return m_isInverted; } * * @param output Write out the PWM value as was found in the PIDController */ -void PWMSpeedController::PIDWrite(float output) { Set(output); } +void PWMSpeedController::PIDWrite(double output) { Set(output); } /** * Common interface to stop the motor until Set is called again. diff --git a/wpilibc/athena/src/PowerDistributionPanel.cpp b/wpilibc/athena/src/PowerDistributionPanel.cpp index 18581e7877..3f659b788c 100644 --- a/wpilibc/athena/src/PowerDistributionPanel.cpp +++ b/wpilibc/athena/src/PowerDistributionPanel.cpp @@ -36,11 +36,11 @@ PowerDistributionPanel::PowerDistributionPanel(int module) : m_module(module) { * * @return The voltage of the PDP in volts */ -float PowerDistributionPanel::GetVoltage() const { +double PowerDistributionPanel::GetVoltage() const { if (StatusIsFatal()) return 0; int32_t status = 0; - float voltage = HAL_GetPDPVoltage(m_module, &status); + double voltage = HAL_GetPDPVoltage(m_module, &status); if (status) { wpi_setWPIErrorWithContext(Timeout, ""); @@ -54,11 +54,11 @@ float PowerDistributionPanel::GetVoltage() const { * * @return The temperature of the PDP in degrees Celsius */ -float PowerDistributionPanel::GetTemperature() const { +double PowerDistributionPanel::GetTemperature() const { if (StatusIsFatal()) return 0; int32_t status = 0; - float temperature = HAL_GetPDPTemperature(m_module, &status); + double temperature = HAL_GetPDPTemperature(m_module, &status); if (status) { wpi_setWPIErrorWithContext(Timeout, ""); @@ -72,7 +72,7 @@ float PowerDistributionPanel::GetTemperature() const { * * @return The current of one of the PDP channels (channels 0-15) in Amperes */ -float PowerDistributionPanel::GetCurrent(int channel) const { +double PowerDistributionPanel::GetCurrent(int channel) const { if (StatusIsFatal()) return 0; int32_t status = 0; @@ -82,7 +82,7 @@ float PowerDistributionPanel::GetCurrent(int channel) const { wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf.str()); } - float current = HAL_GetPDPChannelCurrent(m_module, channel, &status); + double current = HAL_GetPDPChannelCurrent(m_module, channel, &status); if (status) { wpi_setWPIErrorWithContext(Timeout, ""); @@ -96,11 +96,11 @@ float PowerDistributionPanel::GetCurrent(int channel) const { * * @return The the total current drawn from the PDP channels in Amperes */ -float PowerDistributionPanel::GetTotalCurrent() const { +double PowerDistributionPanel::GetTotalCurrent() const { if (StatusIsFatal()) return 0; int32_t status = 0; - float current = HAL_GetPDPTotalCurrent(m_module, &status); + double current = HAL_GetPDPTotalCurrent(m_module, &status); if (status) { wpi_setWPIErrorWithContext(Timeout, ""); @@ -114,11 +114,11 @@ float PowerDistributionPanel::GetTotalCurrent() const { * * @return The the total power drawn from the PDP channels in Watts */ -float PowerDistributionPanel::GetTotalPower() const { +double PowerDistributionPanel::GetTotalPower() const { if (StatusIsFatal()) return 0; int32_t status = 0; - float power = HAL_GetPDPTotalPower(m_module, &status); + double power = HAL_GetPDPTotalPower(m_module, &status); if (status) { wpi_setWPIErrorWithContext(Timeout, ""); @@ -132,11 +132,11 @@ float PowerDistributionPanel::GetTotalPower() const { * * @return The the total energy drawn from the PDP channels in Joules */ -float PowerDistributionPanel::GetTotalEnergy() const { +double PowerDistributionPanel::GetTotalEnergy() const { if (StatusIsFatal()) return 0; int32_t status = 0; - float energy = HAL_GetPDPTotalEnergy(m_module, &status); + double energy = HAL_GetPDPTotalEnergy(m_module, &status); if (status) { wpi_setWPIErrorWithContext(Timeout, ""); diff --git a/wpilibc/athena/src/Preferences.cpp b/wpilibc/athena/src/Preferences.cpp index 122a311c62..5813770800 100644 --- a/wpilibc/athena/src/Preferences.cpp +++ b/wpilibc/athena/src/Preferences.cpp @@ -94,7 +94,7 @@ double Preferences::GetDouble(llvm::StringRef key, double defaultValue) { * @return either the value in the table, or the defaultValue */ float Preferences::GetFloat(llvm::StringRef key, float defaultValue) { - return static_cast(m_table->GetNumber(key, defaultValue)); + return m_table->GetNumber(key, defaultValue); } /** diff --git a/wpilibc/athena/src/Relay.cpp b/wpilibc/athena/src/Relay.cpp index ae354a674d..9acec570a4 100644 --- a/wpilibc/athena/src/Relay.cpp +++ b/wpilibc/athena/src/Relay.cpp @@ -214,7 +214,7 @@ int Relay::GetChannel() const { return m_channel; } * Set the expiration time for the Relay object * @param timeout The timeout (in seconds) for this relay object */ -void Relay::SetExpiration(float timeout) { +void Relay::SetExpiration(double timeout) { m_safetyHelper->SetExpiration(timeout); } @@ -222,7 +222,7 @@ void Relay::SetExpiration(float timeout) { * Return the expiration time for the relay object. * @return The expiration time value. */ -float Relay::GetExpiration() const { return m_safetyHelper->GetExpiration(); } +double Relay::GetExpiration() const { return m_safetyHelper->GetExpiration(); } /** * Check if the relay object is currently alive or stopped due to a timeout. diff --git a/wpilibc/athena/src/RobotDrive.cpp b/wpilibc/athena/src/RobotDrive.cpp index aa4373987c..60b07ae925 100644 --- a/wpilibc/athena/src/RobotDrive.cpp +++ b/wpilibc/athena/src/RobotDrive.cpp @@ -214,8 +214,8 @@ RobotDrive::RobotDrive(std::shared_ptr frontLeftMotor, * Conversely, turn radius r = -ln(curve)*w for a given value of curve and * wheelbase w. */ -void RobotDrive::Drive(float outputMagnitude, float curve) { - float leftOutput, rightOutput; +void RobotDrive::Drive(double outputMagnitude, double curve) { + double leftOutput, rightOutput; static bool reported = false; if (!reported) { HAL_Report(HALUsageReporting::kResourceType_RobotDrive, GetNumMotors(), @@ -224,14 +224,14 @@ void RobotDrive::Drive(float outputMagnitude, float curve) { } if (curve < 0) { - float value = std::log(-curve); - float ratio = (value - m_sensitivity) / (value + m_sensitivity); + double value = std::log(-curve); + double ratio = (value - m_sensitivity) / (value + m_sensitivity); if (ratio == 0) ratio = .0000000001; leftOutput = outputMagnitude / ratio; rightOutput = outputMagnitude; } else if (curve > 0) { - float value = std::log(curve); - float ratio = (value - m_sensitivity) / (value + m_sensitivity); + double value = std::log(curve); + double ratio = (value - m_sensitivity) / (value + m_sensitivity); if (ratio == 0) ratio = .0000000001; leftOutput = outputMagnitude; rightOutput = outputMagnitude / ratio; @@ -303,7 +303,7 @@ void RobotDrive::TankDrive(GenericHID& leftStick, int leftAxis, * @param leftValue The value of the left stick. * @param rightValue The value of the right stick. */ -void RobotDrive::TankDrive(float leftValue, float rightValue, +void RobotDrive::TankDrive(double leftValue, double rightValue, bool squaredInputs) { static bool reported = false; if (!reported) { @@ -387,8 +387,8 @@ void RobotDrive::ArcadeDrive(GenericHID& stick, bool squaredInputs) { void RobotDrive::ArcadeDrive(GenericHID* moveStick, int moveAxis, GenericHID* rotateStick, int rotateAxis, bool squaredInputs) { - float moveValue = moveStick->GetRawAxis(moveAxis); - float rotateValue = rotateStick->GetRawAxis(rotateAxis); + double moveValue = moveStick->GetRawAxis(moveAxis); + double rotateValue = rotateStick->GetRawAxis(rotateAxis); ArcadeDrive(moveValue, rotateValue, squaredInputs); } @@ -412,8 +412,8 @@ void RobotDrive::ArcadeDrive(GenericHID* moveStick, int moveAxis, void RobotDrive::ArcadeDrive(GenericHID& moveStick, int moveAxis, GenericHID& rotateStick, int rotateAxis, bool squaredInputs) { - float moveValue = moveStick.GetRawAxis(moveAxis); - float rotateValue = rotateStick.GetRawAxis(rotateAxis); + double moveValue = moveStick.GetRawAxis(moveAxis); + double rotateValue = rotateStick.GetRawAxis(rotateAxis); ArcadeDrive(moveValue, rotateValue, squaredInputs); } @@ -427,7 +427,7 @@ void RobotDrive::ArcadeDrive(GenericHID& moveStick, int moveAxis, * @param rotateValue The value to use for the rotate right/left * @param squaredInputs If set, increases the sensitivity at low speeds */ -void RobotDrive::ArcadeDrive(float moveValue, float rotateValue, +void RobotDrive::ArcadeDrive(double moveValue, double rotateValue, bool squaredInputs) { static bool reported = false; if (!reported) { @@ -437,8 +437,8 @@ void RobotDrive::ArcadeDrive(float moveValue, float rotateValue, } // local variables to hold the computed PWM values for the motors - float leftMotorOutput; - float rightMotorOutput; + double leftMotorOutput; + double rightMotorOutput; moveValue = Limit(moveValue); rotateValue = Limit(rotateValue); @@ -499,8 +499,8 @@ void RobotDrive::ArcadeDrive(float moveValue, float rotateValue, * @param gyroAngle The current angle reading from the gyro. Use this to * implement field-oriented controls. */ -void RobotDrive::MecanumDrive_Cartesian(float x, float y, float rotation, - float gyroAngle) { +void RobotDrive::MecanumDrive_Cartesian(double x, double y, double rotation, + double gyroAngle) { static bool reported = false; if (!reported) { HAL_Report(HALUsageReporting::kResourceType_RobotDrive, GetNumMotors(), @@ -548,8 +548,8 @@ void RobotDrive::MecanumDrive_Cartesian(float x, float y, float rotation, * @param rotation The rate of rotation for the robot that is completely * independent of the magnitute or direction. [-1.0..1.0] */ -void RobotDrive::MecanumDrive_Polar(float magnitude, float direction, - float rotation) { +void RobotDrive::MecanumDrive_Polar(double magnitude, double direction, + double rotation) { static bool reported = false; if (!reported) { HAL_Report(HALUsageReporting::kResourceType_RobotDrive, GetNumMotors(), @@ -592,8 +592,8 @@ void RobotDrive::MecanumDrive_Polar(float magnitude, float direction, * @param rotation The rate of rotation for the robot that is completely * independent of the magnitude or direction. [-1.0..1.0] */ -void RobotDrive::HolonomicDrive(float magnitude, float direction, - float rotation) { +void RobotDrive::HolonomicDrive(double magnitude, double direction, + double rotation) { MecanumDrive_Polar(magnitude, direction, rotation); } @@ -607,7 +607,8 @@ void RobotDrive::HolonomicDrive(float magnitude, float direction, * @param leftOutput The speed to send to the left side of the robot. * @param rightOutput The speed to send to the right side of the robot. */ -void RobotDrive::SetLeftRightMotorOutputs(float leftOutput, float rightOutput) { +void RobotDrive::SetLeftRightMotorOutputs(double leftOutput, + double rightOutput) { wpi_assert(m_rearLeftMotor != nullptr && m_rearRightMotor != nullptr); if (m_frontLeftMotor != nullptr) @@ -624,7 +625,7 @@ void RobotDrive::SetLeftRightMotorOutputs(float leftOutput, float rightOutput) { /** * Limit motor values to the -1.0 to +1.0 range. */ -float RobotDrive::Limit(float num) { +double RobotDrive::Limit(double num) { if (num > 1.0) { return 1.0; } @@ -702,7 +703,7 @@ void RobotDrive::SetInvertedMotor(MotorType motor, bool isInverted) { * @param sensitivity Effectively sets the turning sensitivity (or turn radius * for a given value) */ -void RobotDrive::SetSensitivity(float sensitivity) { +void RobotDrive::SetSensitivity(double sensitivity) { m_sensitivity = sensitivity; } @@ -715,11 +716,11 @@ void RobotDrive::SetSensitivity(float sensitivity) { */ void RobotDrive::SetMaxOutput(double maxOutput) { m_maxOutput = maxOutput; } -void RobotDrive::SetExpiration(float timeout) { +void RobotDrive::SetExpiration(double timeout) { m_safetyHelper->SetExpiration(timeout); } -float RobotDrive::GetExpiration() const { +double RobotDrive::GetExpiration() const { return m_safetyHelper->GetExpiration(); } diff --git a/wpilibc/athena/src/SafePWM.cpp b/wpilibc/athena/src/SafePWM.cpp index 9d98fec15d..b5500d355a 100644 --- a/wpilibc/athena/src/SafePWM.cpp +++ b/wpilibc/athena/src/SafePWM.cpp @@ -25,7 +25,7 @@ SafePWM::SafePWM(int channel) : PWM(channel) { * * @param timeout The timeout (in seconds) for this motor object */ -void SafePWM::SetExpiration(float timeout) { +void SafePWM::SetExpiration(double timeout) { m_safetyHelper->SetExpiration(timeout); } @@ -34,7 +34,9 @@ void SafePWM::SetExpiration(float timeout) { * * @returns The expiration time value. */ -float SafePWM::GetExpiration() const { return m_safetyHelper->GetExpiration(); } +double SafePWM::GetExpiration() const { + return m_safetyHelper->GetExpiration(); +} /** * Check if the PWM object is currently alive or stopped due to a timeout. @@ -84,7 +86,7 @@ void SafePWM::GetDescription(std::ostringstream& desc) const { * * @param speed Value to pass to the PWM class */ -void SafePWM::SetSpeed(float speed) { +void SafePWM::SetSpeed(double speed) { PWM::SetSpeed(speed); m_safetyHelper->Feed(); } diff --git a/wpilibc/athena/src/SerialPort.cpp b/wpilibc/athena/src/SerialPort.cpp index e998d570cc..4c892d0ebd 100644 --- a/wpilibc/athena/src/SerialPort.cpp +++ b/wpilibc/athena/src/SerialPort.cpp @@ -44,7 +44,7 @@ SerialPort::SerialPort(int baudRate, Port port, int dataBits, wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); // Set the default timeout to 5 seconds. - SetTimeout(5.0f); + SetTimeout(5.0); // Don't wait until the buffer is full to transmit. SetWriteBufferMode(kFlushOnAccess); @@ -150,7 +150,7 @@ int SerialPort::Write(const std::string& buffer, int count) { * * @param timeout The number of seconds to to wait for I/O. */ -void SerialPort::SetTimeout(float timeout) { +void SerialPort::SetTimeout(double timeout) { int32_t status = 0; HAL_SetSerialTimeout(m_port, timeout, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); diff --git a/wpilibc/athena/src/Servo.cpp b/wpilibc/athena/src/Servo.cpp index 9cc012431d..718e842a7c 100644 --- a/wpilibc/athena/src/Servo.cpp +++ b/wpilibc/athena/src/Servo.cpp @@ -11,11 +11,11 @@ using namespace frc; -constexpr float Servo::kMaxServoAngle; -constexpr float Servo::kMinServoAngle; +constexpr double Servo::kMaxServoAngle; +constexpr double Servo::kMinServoAngle; -constexpr float Servo::kDefaultMaxServoPWM; -constexpr float Servo::kDefaultMinServoPWM; +constexpr double Servo::kDefaultMaxServoPWM; +constexpr double Servo::kDefaultMinServoPWM; /** * @param channel The PWM channel to which the servo is attached. 0-9 are @@ -45,7 +45,7 @@ Servo::~Servo() { * * @param value Position from 0.0 to 1.0. */ -void Servo::Set(float value) { SetPosition(value); } +void Servo::Set(double value) { SetPosition(value); } /** * Set the servo to offline. @@ -62,7 +62,7 @@ void Servo::SetOffline() { SetRaw(0); } * * @return Position from 0.0 to 1.0. */ -float Servo::Get() const { return GetPosition(); } +double Servo::Get() const { return GetPosition(); } /** * Set the servo angle. @@ -78,15 +78,14 @@ float Servo::Get() const { return GetPosition(); } * * @param degrees The angle in degrees to set the servo. */ -void Servo::SetAngle(float degrees) { +void Servo::SetAngle(double degrees) { if (degrees < kMinServoAngle) { degrees = kMinServoAngle; } else if (degrees > kMaxServoAngle) { degrees = kMaxServoAngle; } - SetPosition(static_cast(degrees - kMinServoAngle) / - GetServoAngleRange()); + SetPosition((degrees - kMinServoAngle) / GetServoAngleRange()); } /** @@ -97,9 +96,8 @@ void Servo::SetAngle(float degrees) { * * @return The angle in degrees to which the servo is set. */ -float Servo::GetAngle() const { - return static_cast(GetPosition()) * GetServoAngleRange() + - kMinServoAngle; +double Servo::GetAngle() const { + return GetPosition() * GetServoAngleRange() + kMinServoAngle; } void Servo::ValueChanged(ITable* source, llvm::StringRef key, diff --git a/wpilibc/athena/src/XboxController.cpp b/wpilibc/athena/src/XboxController.cpp index 86914f34e9..c328788862 100644 --- a/wpilibc/athena/src/XboxController.cpp +++ b/wpilibc/athena/src/XboxController.cpp @@ -31,7 +31,7 @@ XboxController::XboxController(int port) * * @param hand Side of controller whose value should be returned. */ -float XboxController::GetX(JoystickHand hand) const { +double XboxController::GetX(JoystickHand hand) const { if (hand == kLeftHand) { return GetRawAxis(0); } else { @@ -44,7 +44,7 @@ float XboxController::GetX(JoystickHand hand) const { * * @param hand Side of controller whose value should be returned. */ -float XboxController::GetY(JoystickHand hand) const { +double XboxController::GetY(JoystickHand hand) const { if (hand == kLeftHand) { return GetRawAxis(1); } else { @@ -84,7 +84,7 @@ bool XboxController::GetStickButton(JoystickHand hand) const { * * @param hand Side of controller whose value should be returned. */ -float XboxController::GetTriggerAxis(JoystickHand hand) const { +double XboxController::GetTriggerAxis(JoystickHand hand) const { if (hand == kLeftHand) { return GetRawAxis(2); } else { diff --git a/wpilibc/shared/include/Commands/PIDCommand.h b/wpilibc/shared/include/Commands/PIDCommand.h index bebaa76ff5..39fd1f6934 100644 --- a/wpilibc/shared/include/Commands/PIDCommand.h +++ b/wpilibc/shared/include/Commands/PIDCommand.h @@ -32,7 +32,7 @@ class PIDCommand : public Command, public PIDOutput, public PIDSource { void SetSetpointRelative(double deltaSetpoint); // PIDOutput interface - virtual void PIDWrite(float output); + virtual void PIDWrite(double output); // PIDSource interface virtual double PIDGet(); diff --git a/wpilibc/shared/include/Commands/PIDSubsystem.h b/wpilibc/shared/include/Commands/PIDSubsystem.h index 1802d63e4d..ebfece4149 100644 --- a/wpilibc/shared/include/Commands/PIDSubsystem.h +++ b/wpilibc/shared/include/Commands/PIDSubsystem.h @@ -42,20 +42,20 @@ class PIDSubsystem : public Subsystem, public PIDOutput, public PIDSource { void Disable(); // PIDOutput interface - virtual void PIDWrite(float output); + virtual void PIDWrite(double output); // PIDSource interface virtual double PIDGet(); void SetSetpoint(double setpoint); void SetSetpointRelative(double deltaSetpoint); - void SetInputRange(float minimumInput, float maximumInput); - void SetOutputRange(float minimumOutput, float maximumOutput); + void SetInputRange(double minimumInput, double maximumInput); + void SetOutputRange(double minimumOutput, double maximumOutput); double GetSetpoint(); double GetPosition(); double GetRate(); - virtual void SetAbsoluteTolerance(float absValue); - virtual void SetPercentTolerance(float percent); + virtual void SetAbsoluteTolerance(double absValue); + virtual void SetPercentTolerance(double percent); virtual bool OnTarget() const; protected: diff --git a/wpilibc/shared/include/GenericHID.h b/wpilibc/shared/include/GenericHID.h index ad22d0f6b0..d11bf4a19e 100644 --- a/wpilibc/shared/include/GenericHID.h +++ b/wpilibc/shared/include/GenericHID.h @@ -47,9 +47,9 @@ class GenericHID { explicit GenericHID(int port); virtual ~GenericHID() = default; - virtual float GetX(JoystickHand hand = kRightHand) const = 0; - virtual float GetY(JoystickHand hand = kRightHand) const = 0; - virtual float GetRawAxis(int axis) const; + virtual double GetX(JoystickHand hand = kRightHand) const = 0; + virtual double GetY(JoystickHand hand = kRightHand) const = 0; + virtual double GetRawAxis(int axis) const; bool GetRawButton(int button) const; diff --git a/wpilibc/shared/include/Joystick.h b/wpilibc/shared/include/Joystick.h index 31b01e3275..18b52b3564 100644 --- a/wpilibc/shared/include/Joystick.h +++ b/wpilibc/shared/include/Joystick.h @@ -58,21 +58,21 @@ class Joystick : public JoystickBase, public ErrorBase { int GetAxisChannel(AxisType axis) const; void SetAxisChannel(AxisType axis, int channel); - float GetX(JoystickHand hand = kRightHand) const override; - float GetY(JoystickHand hand = kRightHand) const override; - float GetZ(JoystickHand hand = kRightHand) const override; - float GetTwist() const override; - float GetThrottle() const override; - virtual float GetAxis(AxisType axis) const; + double GetX(JoystickHand hand = kRightHand) const override; + double GetY(JoystickHand hand = kRightHand) const override; + double GetZ(JoystickHand hand = kRightHand) const override; + double GetTwist() const override; + double GetThrottle() const override; + virtual double GetAxis(AxisType axis) const; bool GetTrigger(JoystickHand hand = kRightHand) const override; bool GetTop(JoystickHand hand = kRightHand) const override; bool GetButton(ButtonType button) const; static Joystick* GetStickForPort(int port); - virtual float GetMagnitude() const; - virtual float GetDirectionRadians() const; - virtual float GetDirectionDegrees() const; + virtual double GetMagnitude() const; + virtual double GetDirectionRadians() const; + virtual double GetDirectionDegrees() const; int GetAxisType(int axis) const; diff --git a/wpilibc/shared/include/JoystickBase.h b/wpilibc/shared/include/JoystickBase.h index 2b0f4fcc5b..532e111dbd 100644 --- a/wpilibc/shared/include/JoystickBase.h +++ b/wpilibc/shared/include/JoystickBase.h @@ -19,9 +19,9 @@ class JoystickBase : public GenericHID { explicit JoystickBase(int port); virtual ~JoystickBase() = default; - virtual float GetZ(JoystickHand hand = kRightHand) const = 0; - virtual float GetTwist() const = 0; - virtual float GetThrottle() const = 0; + virtual double GetZ(JoystickHand hand = kRightHand) const = 0; + virtual double GetTwist() const = 0; + virtual double GetThrottle() const = 0; virtual bool GetTrigger(JoystickHand hand = kRightHand) const = 0; virtual bool GetTop(JoystickHand hand = kRightHand) const = 0; diff --git a/wpilibc/shared/include/PIDController.h b/wpilibc/shared/include/PIDController.h index 9dbc810901..7c48097174 100644 --- a/wpilibc/shared/include/PIDController.h +++ b/wpilibc/shared/include/PIDController.h @@ -39,19 +39,19 @@ class PIDController : public LiveWindowSendable, public PIDInterface, public ITableListener { public: - PIDController(float p, float i, float d, PIDSource* source, PIDOutput* output, - float period = 0.05); - PIDController(float p, float i, float d, float f, PIDSource* source, - PIDOutput* output, float period = 0.05); + PIDController(double p, double i, double d, PIDSource* source, + PIDOutput* output, double period = 0.05); + PIDController(double p, double i, double d, double f, PIDSource* source, + PIDOutput* output, double period = 0.05); virtual ~PIDController(); PIDController(const PIDController&) = delete; PIDController& operator=(const PIDController) = delete; - virtual float Get() const; + virtual double Get() const; virtual void SetContinuous(bool continuous = true); - virtual void SetInputRange(float minimumInput, float maximumInput); - virtual void SetOutputRange(float minimumOutput, float maximumOutput); + virtual void SetInputRange(double minimumInput, double maximumInput); + virtual void SetOutputRange(double minimumOutput, double maximumOutput); void SetPID(double p, double i, double d) override; virtual void SetPID(double p, double i, double d, double f); double GetP() const override; @@ -59,19 +59,19 @@ class PIDController : public LiveWindowSendable, double GetD() const override; virtual double GetF() const; - void SetSetpoint(float setpoint) override; + void SetSetpoint(double setpoint) override; double GetSetpoint() const override; double GetDeltaSetpoint() const; - virtual float GetError() const; - virtual float GetAvgError() const; + virtual double GetError() const; + virtual double GetAvgError() const; virtual void SetPIDSourceType(PIDSourceType pidSource); virtual PIDSourceType GetPIDSourceType() const; - virtual void SetTolerance(float percent); - virtual void SetAbsoluteTolerance(float absValue); - virtual void SetPercentTolerance(float percentValue); + virtual void SetTolerance(double percent); + virtual void SetAbsoluteTolerance(double absValue); + virtual void SetPercentTolerance(double percentValue); virtual void SetToleranceBuffer(int buf = 1); virtual bool OnTarget() const; @@ -94,27 +94,27 @@ class PIDController : public LiveWindowSendable, private: // factor for "proportional" control - float m_P; + double m_P; // factor for "integral" control - float m_I; + double m_I; // factor for "derivative" control - float m_D; + double m_D; // factor for "feed forward" control - float m_F; + double m_F; // |maximum output| - float m_maximumOutput = 1.0; + double m_maximumOutput = 1.0; // |minimum output| - float m_minimumOutput = -1.0; + double m_minimumOutput = -1.0; // maximum input - limit setpoint to this - float m_maximumInput = 0; + double m_maximumInput = 0; // minimum input - limit setpoint to this - float m_minimumInput = 0; + double m_minimumInput = 0; // do the endpoints wrap around? eg. Absolute encoder bool m_continuous = false; // is the pid controller enabled bool m_enabled = false; // the prior error (used to compute velocity) - float m_prevError = 0; + double m_prevError = 0; // the sum of the errors for use in the integral calc double m_totalError = 0; enum { @@ -124,12 +124,12 @@ class PIDController : public LiveWindowSendable, } m_toleranceType = kNoTolerance; // the percetage or absolute error that is considered on target. - float m_tolerance = 0.05; - float m_setpoint = 0; - float m_prevSetpoint = 0; - float m_error = 0; - float m_result = 0; - float m_period; + double m_tolerance = 0.05; + double m_setpoint = 0; + double m_prevSetpoint = 0; + double m_error = 0; + double m_result = 0; + double m_period; // Length of buffer for averaging for tolerances. std::atomic m_bufLength{1}; diff --git a/wpilibc/shared/include/PIDInterface.h b/wpilibc/shared/include/PIDInterface.h index 62b40e29c3..1393a06144 100644 --- a/wpilibc/shared/include/PIDInterface.h +++ b/wpilibc/shared/include/PIDInterface.h @@ -19,7 +19,7 @@ class PIDInterface : public Controller { virtual double GetI() const = 0; virtual double GetD() const = 0; - virtual void SetSetpoint(float setpoint) = 0; + virtual void SetSetpoint(double setpoint) = 0; virtual double GetSetpoint() const = 0; virtual void Enable() = 0; diff --git a/wpilibc/shared/include/PIDOutput.h b/wpilibc/shared/include/PIDOutput.h index 63b166c8c0..f076b0d5aa 100644 --- a/wpilibc/shared/include/PIDOutput.h +++ b/wpilibc/shared/include/PIDOutput.h @@ -19,7 +19,7 @@ namespace frc { */ class PIDOutput { public: - virtual void PIDWrite(float output) = 0; + virtual void PIDWrite(double output) = 0; }; } // namespace frc diff --git a/wpilibc/shared/include/XboxController.h b/wpilibc/shared/include/XboxController.h index 67855729c0..ebc86f6570 100644 --- a/wpilibc/shared/include/XboxController.h +++ b/wpilibc/shared/include/XboxController.h @@ -31,13 +31,13 @@ class XboxController : public GamepadBase, public ErrorBase { XboxController(const XboxController&) = delete; XboxController& operator=(const XboxController&) = delete; - float GetX(JoystickHand hand) const override; - float GetY(JoystickHand hand) const override; + double GetX(JoystickHand hand) const override; + double GetY(JoystickHand hand) const override; bool GetBumper(JoystickHand hand) const override; bool GetStickButton(JoystickHand hand) const override; - virtual float GetTriggerAxis(JoystickHand hand) const; + virtual double GetTriggerAxis(JoystickHand hand) const; bool GetAButton() const; bool GetBButton() const; diff --git a/wpilibc/shared/include/interfaces/Gyro.h b/wpilibc/shared/include/interfaces/Gyro.h index ffb39a9fbf..5e9b5f44d9 100644 --- a/wpilibc/shared/include/interfaces/Gyro.h +++ b/wpilibc/shared/include/interfaces/Gyro.h @@ -45,7 +45,7 @@ class Gyro { * @return the current heading of the robot in degrees. This heading is based * on integration of the returned rate from the gyro. */ - virtual float GetAngle() const = 0; + virtual double GetAngle() const = 0; /** * Return the rate of rotation of the gyro diff --git a/wpilibc/shared/src/Commands/PIDCommand.cpp b/wpilibc/shared/src/Commands/PIDCommand.cpp index 0318cb2060..b5626ce69f 100644 --- a/wpilibc/shared/src/Commands/PIDCommand.cpp +++ b/wpilibc/shared/src/Commands/PIDCommand.cpp @@ -51,7 +51,7 @@ void PIDCommand::SetSetpointRelative(double deltaSetpoint) { SetSetpoint(GetSetpoint() + deltaSetpoint); } -void PIDCommand::PIDWrite(float output) { UsePIDOutput(output); } +void PIDCommand::PIDWrite(double output) { UsePIDOutput(output); } double PIDCommand::PIDGet() { return ReturnPIDInput(); } diff --git a/wpilibc/shared/src/Commands/PIDSubsystem.cpp b/wpilibc/shared/src/Commands/PIDSubsystem.cpp index f3563756d2..4b277d90ef 100644 --- a/wpilibc/shared/src/Commands/PIDSubsystem.cpp +++ b/wpilibc/shared/src/Commands/PIDSubsystem.cpp @@ -172,7 +172,7 @@ double PIDSubsystem::GetSetpoint() { return m_controller->GetSetpoint(); } * @param minimumInput the minimum value expected from the input * @param maximumInput the maximum value expected from the output */ -void PIDSubsystem::SetInputRange(float minimumInput, float maximumInput) { +void PIDSubsystem::SetInputRange(double minimumInput, double maximumInput) { m_controller->SetInputRange(minimumInput, maximumInput); } @@ -182,7 +182,7 @@ void PIDSubsystem::SetInputRange(float minimumInput, float maximumInput) { * @param minimumOutput the minimum value to write to the output * @param maximumOutput the maximum value to write to the output */ -void PIDSubsystem::SetOutputRange(float minimumOutput, float maximumOutput) { +void PIDSubsystem::SetOutputRange(double minimumOutput, double maximumOutput) { m_controller->SetOutputRange(minimumOutput, maximumOutput); } @@ -192,7 +192,7 @@ void PIDSubsystem::SetOutputRange(float minimumOutput, float maximumOutput) { * * @param absValue absolute error which is tolerable */ -void PIDSubsystem::SetAbsoluteTolerance(float absValue) { +void PIDSubsystem::SetAbsoluteTolerance(double absValue) { m_controller->SetAbsoluteTolerance(absValue); } @@ -201,7 +201,7 @@ void PIDSubsystem::SetAbsoluteTolerance(float absValue) { * * @param percent percentage error which is tolerable */ -void PIDSubsystem::SetPercentTolerance(float percent) { +void PIDSubsystem::SetPercentTolerance(double percent) { m_controller->SetPercentTolerance(percent); } @@ -236,7 +236,7 @@ double PIDSubsystem::GetPosition() { return ReturnPIDInput(); } */ double PIDSubsystem::GetRate() { return ReturnPIDInput(); } -void PIDSubsystem::PIDWrite(float output) { UsePIDOutput(output); } +void PIDSubsystem::PIDWrite(double output) { UsePIDOutput(output); } double PIDSubsystem::PIDGet() { return ReturnPIDInput(); } diff --git a/wpilibc/sim/include/AnalogGyro.h b/wpilibc/sim/include/AnalogGyro.h index 2219683f8e..16ac04e6dd 100644 --- a/wpilibc/sim/include/AnalogGyro.h +++ b/wpilibc/sim/include/AnalogGyro.h @@ -33,13 +33,13 @@ class AnalogGyro : public GyroBase { public: static const int kOversampleBits; static const int kAverageBits; - static const float kSamplesPerSecond; - static const float kCalibrationSampleTime; - static const float kDefaultVoltsPerDegreePerSecond; + static const double kSamplesPerSecond; + static const double kCalibrationSampleTime; + static const double kDefaultVoltsPerDegreePerSecond; explicit AnalogGyro(int channel); virtual ~AnalogGyro() = default; - float GetAngle() const; + double GetAngle() const; void Calibrate() override; double GetRate() const; void Reset(); diff --git a/wpilibc/sim/include/AnalogInput.h b/wpilibc/sim/include/AnalogInput.h index b9fa21f8e2..922f89cfb0 100644 --- a/wpilibc/sim/include/AnalogInput.h +++ b/wpilibc/sim/include/AnalogInput.h @@ -40,8 +40,8 @@ class AnalogInput : public SensorBase, explicit AnalogInput(int channel); virtual ~AnalogInput() = default; - float GetVoltage() const; - float GetAverageVoltage() const; + double GetVoltage() const; + double GetAverageVoltage() const; int GetChannel() const; diff --git a/wpilibc/sim/include/Counter.h b/wpilibc/sim/include/Counter.h index b4178bff3f..fcbb4aaac6 100644 --- a/wpilibc/sim/include/Counter.h +++ b/wpilibc/sim/include/Counter.h @@ -63,7 +63,7 @@ class Counter : public SensorBase, void SetUpDownCounterMode(); void SetExternalDirectionMode(); void SetSemiPeriodMode(bool highSemiPeriod); - void SetPulseLengthMode(float threshold); + void SetPulseLengthMode(double threshold); void SetReverseDirection(bool reverseDirection); diff --git a/wpilibc/sim/include/DriverStation.h b/wpilibc/sim/include/DriverStation.h index b5bc2156e0..8d9818f4b2 100644 --- a/wpilibc/sim/include/DriverStation.h +++ b/wpilibc/sim/include/DriverStation.h @@ -48,11 +48,11 @@ class DriverStation : public SensorBase, public RobotStateInterface { static const int kJoystickPorts = 4; static const int kJoystickAxes = 6; - float GetStickAxis(int stick, int axis); + double GetStickAxis(int stick, int axis); bool GetStickButton(int stick, int button); int16_t GetStickButtons(int stick); - float GetAnalogIn(int channel); + double GetAnalogIn(int channel); bool GetDigitalIn(int channel); void SetDigitalOut(int channel, bool value); bool GetDigitalOut(int channel); @@ -70,7 +70,7 @@ class DriverStation : public SensorBase, public RobotStateInterface { void WaitForData(); bool WaitForData(double timeout); double GetMatchTime() const; - float GetBatteryVoltage() const; + double GetBatteryVoltage() const; uint16_t GetTeamNumber() const; void IncrementUpdateNumber() { m_updateNumber++; } @@ -115,7 +115,7 @@ class DriverStation : public SensorBase, public RobotStateInterface { static DriverStation* m_instance; static int m_updateNumber; ///< TODO: Get rid of this and use the semaphore signaling - static const float kUpdatePeriod; + static const double kUpdatePeriod; void stateCallback(const gazebo::msgs::ConstDriverStationPtr& msg); void joystickCallback(const gazebo::msgs::ConstFRCJoystickPtr& msg, int i); diff --git a/wpilibc/sim/include/Jaguar.h b/wpilibc/sim/include/Jaguar.h index 5c1eb72ce6..3c346249c2 100644 --- a/wpilibc/sim/include/Jaguar.h +++ b/wpilibc/sim/include/Jaguar.h @@ -20,11 +20,11 @@ class Jaguar : public SafePWM, public SpeedController { public: explicit Jaguar(int channel); virtual ~Jaguar() = default; - virtual void Set(float value); - virtual float Get() const; + virtual void Set(double value); + virtual double Get() const; virtual void Disable(); - void PIDWrite(float output) override; + void PIDWrite(double output) override; }; } // namespace frc diff --git a/wpilibc/sim/include/MotorSafety.h b/wpilibc/sim/include/MotorSafety.h index 8b67ab50f9..1d6164b82c 100644 --- a/wpilibc/sim/include/MotorSafety.h +++ b/wpilibc/sim/include/MotorSafety.h @@ -15,8 +15,8 @@ namespace frc { class MotorSafety { public: - virtual void SetExpiration(float timeout) = 0; - virtual float GetExpiration() const = 0; + virtual void SetExpiration(double timeout) = 0; + virtual double GetExpiration() const = 0; virtual bool IsAlive() const = 0; virtual void StopMotor() = 0; virtual void SetSafetyEnabled(bool enabled) = 0; diff --git a/wpilibc/sim/include/MotorSafetyHelper.h b/wpilibc/sim/include/MotorSafetyHelper.h index c0cde84df0..40df5d23e3 100644 --- a/wpilibc/sim/include/MotorSafetyHelper.h +++ b/wpilibc/sim/include/MotorSafetyHelper.h @@ -21,8 +21,8 @@ class MotorSafetyHelper : public ErrorBase { explicit MotorSafetyHelper(MotorSafety* safeObject); ~MotorSafetyHelper(); void Feed(); - void SetExpiration(float expirationTime); - float GetExpiration() const; + void SetExpiration(double expirationTime); + double GetExpiration() const; bool IsAlive() const; void Check(); void SetSafetyEnabled(bool enabled); diff --git a/wpilibc/sim/include/PWM.h b/wpilibc/sim/include/PWM.h index 6ef9614bda..1ab78c9851 100644 --- a/wpilibc/sim/include/PWM.h +++ b/wpilibc/sim/include/PWM.h @@ -74,21 +74,21 @@ class PWM : public SensorBase, * scaling is implemented as an output squelch to get longer periods for old * devices. */ - static const float kDefaultPwmPeriod; + static const double kDefaultPwmPeriod; /** * kDefaultPwmCenter is the PWM range center in ms */ - static const float kDefaultPwmCenter; + static const double kDefaultPwmCenter; /** * kDefaultPWMStepsDown is the number of PWM steps below the centerpoint */ static const int kDefaultPwmStepsDown; static const int kPwmDisabled; - virtual void SetPosition(float pos); - virtual float GetPosition() const; - virtual void SetSpeed(float speed); - virtual float GetSpeed() const; + virtual void SetPosition(double pos); + virtual double GetPosition() const; + virtual void SetSpeed(double speed); + virtual double GetSpeed() const; bool m_eliminateDeadband; int m_centerPwm; diff --git a/wpilibc/sim/include/Relay.h b/wpilibc/sim/include/Relay.h index ba31ba933c..4c227f2835 100644 --- a/wpilibc/sim/include/Relay.h +++ b/wpilibc/sim/include/Relay.h @@ -49,8 +49,8 @@ class Relay : public MotorSafety, Value Get() const; int GetChannel() const; - void SetExpiration(float timeout) override; - float GetExpiration() const override; + void SetExpiration(double timeout) override; + double GetExpiration() const override; bool IsAlive() const override; void StopMotor() override; bool IsSafetyEnabled() const override; diff --git a/wpilibc/sim/include/RobotDrive.h b/wpilibc/sim/include/RobotDrive.h index 1bcc35e346..d5e1a7e926 100644 --- a/wpilibc/sim/include/RobotDrive.h +++ b/wpilibc/sim/include/RobotDrive.h @@ -61,7 +61,7 @@ class RobotDrive : public MotorSafety, public ErrorBase { RobotDrive(const RobotDrive&) = delete; RobotDrive& operator=(const RobotDrive&) = delete; - void Drive(float outputMagnitude, float curve); + void Drive(double outputMagnitude, double curve); void TankDrive(GenericHID* leftStick, GenericHID* rightStick, bool squaredInputs = true); void TankDrive(GenericHID& leftStick, GenericHID& rightStick, @@ -70,7 +70,8 @@ class RobotDrive : public MotorSafety, public ErrorBase { int rightAxis, bool squaredInputs = true); void TankDrive(GenericHID& leftStick, int leftAxis, GenericHID& rightStick, int rightAxis, bool squaredInputs = true); - void TankDrive(float leftValue, float rightValue, bool squaredInputs = true); + void TankDrive(double leftValue, double rightValue, + bool squaredInputs = true); void ArcadeDrive(GenericHID* stick, bool squaredInputs = true); void ArcadeDrive(GenericHID& stick, bool squaredInputs = true); void ArcadeDrive(GenericHID* moveStick, int moveChannel, @@ -79,19 +80,19 @@ class RobotDrive : public MotorSafety, public ErrorBase { void ArcadeDrive(GenericHID& moveStick, int moveChannel, GenericHID& rotateStick, int rotateChannel, bool squaredInputs = true); - void ArcadeDrive(float moveValue, float rotateValue, + void ArcadeDrive(double moveValue, double rotateValue, bool squaredInputs = true); - void MecanumDrive_Cartesian(float x, float y, float rotation, - float gyroAngle = 0.0); - void MecanumDrive_Polar(float magnitude, float direction, float rotation); - void HolonomicDrive(float magnitude, float direction, float rotation); - virtual void SetLeftRightMotorOutputs(float leftOutput, float rightOutput); + void MecanumDrive_Cartesian(double x, double y, double rotation, + double gyroAngle = 0.0); + void MecanumDrive_Polar(double magnitude, double direction, double rotation); + void HolonomicDrive(double magnitude, double direction, double rotation); + virtual void SetLeftRightMotorOutputs(double leftOutput, double rightOutput); void SetInvertedMotor(MotorType motor, bool isInverted); - void SetSensitivity(float sensitivity); + void SetSensitivity(double sensitivity); void SetMaxOutput(double maxOutput); - void SetExpiration(float timeout) override; - float GetExpiration() const override; + void SetExpiration(double timeout) override; + double GetExpiration() const override; bool IsAlive() const override; void StopMotor() override; bool IsSafetyEnabled() const override; @@ -100,14 +101,14 @@ class RobotDrive : public MotorSafety, public ErrorBase { protected: void InitRobotDrive(); - float Limit(float num); + double Limit(double num); void Normalize(double* wheelSpeeds); void RotateVector(double& x, double& y, double angle); static const int kMaxNumberOfMotors = 4; int m_invertedMotors[kMaxNumberOfMotors] = {1, 1, 1, 1}; - float m_sensitivity = 0.5; + double m_sensitivity = 0.5; double m_maxOutput = 1.0; bool m_deleteSpeedControllers; std::shared_ptr m_frontLeftMotor; diff --git a/wpilibc/sim/include/SafePWM.h b/wpilibc/sim/include/SafePWM.h index 85c4bdeaad..a92971b715 100644 --- a/wpilibc/sim/include/SafePWM.h +++ b/wpilibc/sim/include/SafePWM.h @@ -28,15 +28,15 @@ class SafePWM : public PWM, public MotorSafety { explicit SafePWM(int channel); virtual ~SafePWM() = default; - void SetExpiration(float timeout); - float GetExpiration() const; + void SetExpiration(double timeout); + double GetExpiration() const; bool IsAlive() const; void StopMotor(); bool IsSafetyEnabled() const; void SetSafetyEnabled(bool enabled); void GetDescription(std::ostringstream& desc) const; - virtual void SetSpeed(float speed); + virtual void SetSpeed(double speed); private: std::unique_ptr m_safetyHelper; diff --git a/wpilibc/sim/include/SpeedController.h b/wpilibc/sim/include/SpeedController.h index 9e7ef275d4..f9c608fff9 100644 --- a/wpilibc/sim/include/SpeedController.h +++ b/wpilibc/sim/include/SpeedController.h @@ -22,13 +22,13 @@ class SpeedController : public PIDOutput { * * @param speed The speed to set. Value should be between -1.0 and 1.0. */ - virtual void Set(float speed) = 0; + virtual void Set(double speed) = 0; /** * Common interface for getting the current set speed of a speed controller. * * @return The current set speed. Value is between -1.0 and 1.0. */ - virtual float Get() const = 0; + virtual double Get() const = 0; /** * Common interface for disabling a motor. */ diff --git a/wpilibc/sim/include/Talon.h b/wpilibc/sim/include/Talon.h index bd6f958ac5..0313ed238f 100644 --- a/wpilibc/sim/include/Talon.h +++ b/wpilibc/sim/include/Talon.h @@ -20,11 +20,11 @@ class Talon : public SafePWM, public SpeedController { public: explicit Talon(int channel); virtual ~Talon() = default; - virtual void Set(float value); - virtual float Get() const; + virtual void Set(double value); + virtual double Get() const; virtual void Disable(); - void PIDWrite(float output) override; + void PIDWrite(double output) override; }; } // namespace frc diff --git a/wpilibc/sim/include/Victor.h b/wpilibc/sim/include/Victor.h index dafe9161e6..a5ffb9e17d 100644 --- a/wpilibc/sim/include/Victor.h +++ b/wpilibc/sim/include/Victor.h @@ -20,11 +20,11 @@ class Victor : public SafePWM, public SpeedController { public: explicit Victor(int channel); virtual ~Victor() = default; - virtual void Set(float value); - virtual float Get() const; + virtual void Set(double value); + virtual double Get() const; virtual void Disable(); - void PIDWrite(float output) override; + void PIDWrite(double output) override; }; } // namespace frc diff --git a/wpilibc/sim/include/simulation/SimContinuousOutput.h b/wpilibc/sim/include/simulation/SimContinuousOutput.h index 0b287a749c..846cd19d53 100644 --- a/wpilibc/sim/include/simulation/SimContinuousOutput.h +++ b/wpilibc/sim/include/simulation/SimContinuousOutput.h @@ -24,7 +24,7 @@ namespace frc { class SimContinuousOutput { private: gazebo::transport::PublisherPtr pub; - float speed; + double speed; public: explicit SimContinuousOutput(std::string topic); @@ -37,12 +37,12 @@ class SimContinuousOutput { * * @param value The value between -1.0 and 1.0 to set. */ - void Set(float value); + void Set(double value); /** * @return The most recently set value. */ - float Get(); + double Get(); }; } // namespace frc diff --git a/wpilibc/sim/src/AnalogGyro.cpp b/wpilibc/sim/src/AnalogGyro.cpp index b116357c47..c78da51cc2 100644 --- a/wpilibc/sim/src/AnalogGyro.cpp +++ b/wpilibc/sim/src/AnalogGyro.cpp @@ -17,9 +17,9 @@ using namespace frc; const int AnalogGyro::kOversampleBits = 10; const int AnalogGyro::kAverageBits = 0; -const float AnalogGyro::kSamplesPerSecond = 50.0; -const float AnalogGyro::kCalibrationSampleTime = 5.0; -const float AnalogGyro::kDefaultVoltsPerDegreePerSecond = 0.007; +const double AnalogGyro::kSamplesPerSecond = 50.0; +const double AnalogGyro::kCalibrationSampleTime = 5.0; +const double AnalogGyro::kDefaultVoltsPerDegreePerSecond = 0.007; /** * Initialize the gyro. @@ -71,7 +71,7 @@ void AnalogGyro::Calibrate() { Reset(); } * @return the current heading of the robot in degrees. This heading is based on * integration of the returned rate from the gyro. */ -float AnalogGyro::GetAngle() const { return impl->GetAngle(); } +double AnalogGyro::GetAngle() const { return impl->GetAngle(); } /** * Return the rate of rotation of the gyro diff --git a/wpilibc/sim/src/AnalogInput.cpp b/wpilibc/sim/src/AnalogInput.cpp index f94f7402ad..f4d6700d50 100644 --- a/wpilibc/sim/src/AnalogInput.cpp +++ b/wpilibc/sim/src/AnalogInput.cpp @@ -35,7 +35,7 @@ AnalogInput::AnalogInput(int channel) : m_channel(channel) { * * @return A scaled sample straight from this channel. */ -float AnalogInput::GetVoltage() const { return m_impl->Get(); } +double AnalogInput::GetVoltage() const { return m_impl->Get(); } /** * Get a scaled sample from the output of the oversample and average engine for @@ -49,7 +49,7 @@ float AnalogInput::GetVoltage() const { return m_impl->Get(); } * @return A scaled sample from the output of the oversample and average engine * for this channel. */ -float AnalogInput::GetAverageVoltage() const { return m_impl->Get(); } +double AnalogInput::GetAverageVoltage() const { return m_impl->Get(); } /** * Get the channel number. diff --git a/wpilibc/sim/src/DriverStation.cpp b/wpilibc/sim/src/DriverStation.cpp index ff7811b0be..e974b6eb9d 100644 --- a/wpilibc/sim/src/DriverStation.cpp +++ b/wpilibc/sim/src/DriverStation.cpp @@ -20,7 +20,7 @@ using namespace frc; const int DriverStation::kBatteryChannel; const int DriverStation::kJoystickPorts; const int DriverStation::kJoystickAxes; -const float DriverStation::kUpdatePeriod = 0.02; +const double DriverStation::kUpdatePeriod = 0.02; int DriverStation::m_updateNumber = 0; /** @@ -66,7 +66,7 @@ DriverStation& DriverStation::GetInstance() { * * @return The battery voltage. */ -float DriverStation::GetBatteryVoltage() const { +double DriverStation::GetBatteryVoltage() const { return 12.0; // 12 volts all the time! } @@ -78,7 +78,7 @@ float DriverStation::GetBatteryVoltage() const { * @param axis The analog axis value to read from the joystick. * @return The value of the axis on the joystick. */ -float DriverStation::GetStickAxis(int stick, int axis) { +double DriverStation::GetStickAxis(int stick, int axis) { if (axis < 0 || axis > (kJoystickAxes - 1)) { wpi_setWPIError(BadJoystickAxis); return 0.0; @@ -147,7 +147,7 @@ int16_t DriverStation::GetStickButtons(int stick) { } // 5V divided by 10 bits -#define kDSAnalogInScaling (static_cast(5.0 / 1023.0)) +#define kDSAnalogInScaling (5.0 / 1023.0) /** * Get an analog voltage from the Driver Station. @@ -161,7 +161,7 @@ int16_t DriverStation::GetStickButtons(int stick) { * Valid range is 1 - 4. * @return The analog voltage on the input. */ -float DriverStation::GetAnalogIn(int channel) { +double DriverStation::GetAnalogIn(int channel) { wpi_setWPIErrorWithContext(UnsupportedInSimulation, "GetAnalogIn"); return 0.0; } diff --git a/wpilibc/sim/src/GenericHID.cpp b/wpilibc/sim/src/GenericHID.cpp index 617d1cd8c4..48cdf14bb2 100644 --- a/wpilibc/sim/src/GenericHID.cpp +++ b/wpilibc/sim/src/GenericHID.cpp @@ -21,7 +21,7 @@ GenericHID::GenericHID(int port) : m_ds(DriverStation::GetInstance()) { * @param axis The axis to read, starting at 0. * @return The value of the axis. */ -float GenericHID::GetRawAxis(int axis) const { +double GenericHID::GetRawAxis(int axis) const { return m_ds.GetStickAxis(m_port, axis); } diff --git a/wpilibc/sim/src/Jaguar.cpp b/wpilibc/sim/src/Jaguar.cpp index 3f17c29557..7baabab819 100644 --- a/wpilibc/sim/src/Jaguar.cpp +++ b/wpilibc/sim/src/Jaguar.cpp @@ -39,14 +39,14 @@ Jaguar::Jaguar(int channel) : SafePWM(channel) { * * @param speed The speed value between -1.0 and 1.0 to set. */ -void Jaguar::Set(float speed) { SetSpeed(speed); } +void Jaguar::Set(double speed) { SetSpeed(speed); } /** * Get the recently set value of the PWM. * * @return The most recently set value for the PWM between -1.0 and 1.0. */ -float Jaguar::Get() const { return GetSpeed(); } +double Jaguar::Get() const { return GetSpeed(); } /** * Common interface for disabling a motor. @@ -58,4 +58,4 @@ void Jaguar::Disable() { SetRaw(kPwmDisabled); } * * @param output Write out the PWM value as was found in the PIDController */ -void Jaguar::PIDWrite(float output) { Set(output); } +void Jaguar::PIDWrite(double output) { Set(output); } diff --git a/wpilibc/sim/src/Joystick.cpp b/wpilibc/sim/src/Joystick.cpp index 5f1f7cbe74..c17c815a90 100644 --- a/wpilibc/sim/src/Joystick.cpp +++ b/wpilibc/sim/src/Joystick.cpp @@ -87,7 +87,7 @@ Joystick* Joystick::GetStickForPort(int port) { * @param hand This parameter is ignored for the Joystick class and is only * here to complete the GenericHID interface. */ -float Joystick::GetX(JoystickHand hand) const { +double Joystick::GetX(JoystickHand hand) const { return GetRawAxis(m_axes[kXAxis]); } @@ -99,7 +99,7 @@ float Joystick::GetX(JoystickHand hand) const { * @param hand This parameter is ignored for the Joystick class and is only * here to complete the GenericHID interface. */ -float Joystick::GetY(JoystickHand hand) const { +double Joystick::GetY(JoystickHand hand) const { return GetRawAxis(m_axes[kYAxis]); } @@ -108,7 +108,7 @@ float Joystick::GetY(JoystickHand hand) const { * * This depends on the mapping of the joystick connected to the current port. */ -float Joystick::GetZ(JoystickHand hand) const { +double Joystick::GetZ(JoystickHand hand) const { return GetRawAxis(m_axes[kZAxis]); } @@ -117,14 +117,14 @@ float Joystick::GetZ(JoystickHand hand) const { * * This depends on the mapping of the joystick connected to the current port. */ -float Joystick::GetTwist() const { return GetRawAxis(m_axes[kTwistAxis]); } +double Joystick::GetTwist() const { return GetRawAxis(m_axes[kTwistAxis]); } /** * Get the throttle value of the current joystick. * * This depends on the mapping of the joystick connected to the current port. */ -float Joystick::GetThrottle() const { +double Joystick::GetThrottle() const { return GetRawAxis(m_axes[kThrottleAxis]); } @@ -138,7 +138,7 @@ float Joystick::GetThrottle() const { * @param axis The axis to read. * @return The value of the axis. */ -float Joystick::GetAxis(AxisType axis) const { +double Joystick::GetAxis(AxisType axis) const { switch (axis) { case kXAxis: return this->GetX(); @@ -246,7 +246,7 @@ void Joystick::SetAxisChannel(AxisType axis, int channel) { * * @return The magnitude of the direction vector */ -float Joystick::GetMagnitude() const { +double Joystick::GetMagnitude() const { return std::sqrt(std::pow(GetX(), 2) + std::pow(GetY(), 2)); } @@ -256,7 +256,7 @@ float Joystick::GetMagnitude() const { * * @return The direction of the vector in radians */ -float Joystick::GetDirectionRadians() const { +double Joystick::GetDirectionRadians() const { return std::atan2(GetX(), -GetY()); } @@ -269,6 +269,6 @@ float Joystick::GetDirectionRadians() const { * * @return The direction of the vector in degrees */ -float Joystick::GetDirectionDegrees() const { +double Joystick::GetDirectionDegrees() const { return (180 / std::acos(-1)) * GetDirectionRadians(); } diff --git a/wpilibc/sim/src/MotorSafetyHelper.cpp b/wpilibc/sim/src/MotorSafetyHelper.cpp index d4bff4d6b2..e7dbc426cd 100644 --- a/wpilibc/sim/src/MotorSafetyHelper.cpp +++ b/wpilibc/sim/src/MotorSafetyHelper.cpp @@ -61,7 +61,7 @@ void MotorSafetyHelper::Feed() { * * @param expirationTime The timeout value in seconds. */ -void MotorSafetyHelper::SetExpiration(float expirationTime) { +void MotorSafetyHelper::SetExpiration(double expirationTime) { std::lock_guard sync(m_syncMutex); m_expiration = expirationTime; } @@ -71,7 +71,7 @@ void MotorSafetyHelper::SetExpiration(float expirationTime) { * * @return the timeout value in seconds. */ -float MotorSafetyHelper::GetExpiration() const { +double MotorSafetyHelper::GetExpiration() const { std::lock_guard sync(m_syncMutex); return m_expiration; } diff --git a/wpilibc/sim/src/PIDController.cpp b/wpilibc/sim/src/PIDController.cpp index ae66db60e5..8c184ec50d 100644 --- a/wpilibc/sim/src/PIDController.cpp +++ b/wpilibc/sim/src/PIDController.cpp @@ -34,9 +34,9 @@ static const std::string kEnabled = "enabled"; * calculations of the integral and differental terms. The * default is 50ms. */ -PIDController::PIDController(float Kp, float Ki, float Kd, PIDSource* source, - PIDOutput* output, float period) - : PIDController(Kp, Ki, Kd, 0.0f, source, output, period) {} +PIDController::PIDController(double Kp, double Ki, double Kd, PIDSource* source, + PIDOutput* output, double period) + : PIDController(Kp, Ki, Kd, 0.0, source, output, period) {} /** * Allocate a PID object with the given constants for P, I, D. @@ -50,9 +50,9 @@ PIDController::PIDController(float Kp, float Ki, float Kd, PIDSource* source, * calculations of the integral and differental terms. The * default is 50ms. */ -PIDController::PIDController(float Kp, float Ki, float Kd, float Kf, +PIDController::PIDController(double Kp, double Ki, double Kd, double Kf, PIDSource* source, PIDOutput* output, - float period) { + double period) { m_table = nullptr; m_P = Kp; @@ -111,8 +111,8 @@ void PIDController::Calculate() { } if (enabled) { - float input = pidInput->PIDGet(); - float result; + double input = pidInput->PIDGet(); + double result; PIDOutput* pidOutput; { @@ -299,7 +299,7 @@ double PIDController::GetF() const { * * @return the latest calculated output */ -float PIDController::Get() const { +double PIDController::Get() const { std::lock_guard lock(m_mutex); return m_result; } @@ -324,7 +324,7 @@ void PIDController::SetContinuous(bool continuous) { * @param minimumInput the minimum value expected from the input * @param maximumInput the maximum value expected from the output */ -void PIDController::SetInputRange(float minimumInput, float maximumInput) { +void PIDController::SetInputRange(double minimumInput, double maximumInput) { { std::lock_guard lock(m_mutex); m_minimumInput = minimumInput; @@ -340,7 +340,7 @@ void PIDController::SetInputRange(float minimumInput, float maximumInput) { * @param minimumOutput the minimum value to write to the output * @param maximumOutput the maximum value to write to the output */ -void PIDController::SetOutputRange(float minimumOutput, float maximumOutput) { +void PIDController::SetOutputRange(double minimumOutput, double maximumOutput) { std::lock_guard lock(m_mutex); m_minimumOutput = minimumOutput; m_maximumOutput = maximumOutput; @@ -351,7 +351,7 @@ void PIDController::SetOutputRange(float minimumOutput, float maximumOutput) { * * @param setpoint the desired setpoint */ -void PIDController::SetSetpoint(float setpoint) { +void PIDController::SetSetpoint(double setpoint) { { std::lock_guard lock(m_mutex); @@ -397,7 +397,7 @@ double PIDController::GetDeltaSetpoint() const { * * @return the current error */ -float PIDController::GetError() const { +double PIDController::GetError() const { double setpoint = GetSetpoint(); { std::lock_guard sync(m_mutex); @@ -429,8 +429,8 @@ PIDSourceType PIDController::GetPIDSourceType() const { * * @return the average error */ -float PIDController::GetAvgError() const { - float avgError = 0; +double PIDController::GetAvgError() const { + double avgError = 0; { std::lock_guard sync(m_mutex); // Don't divide by zero. @@ -445,7 +445,7 @@ float PIDController::GetAvgError() const { * * @param percent percentage error which is tolerable */ -void PIDController::SetTolerance(float percent) { +void PIDController::SetTolerance(double percent) { std::lock_guard lock(m_mutex); m_toleranceType = kPercentTolerance; m_tolerance = percent; @@ -457,7 +457,7 @@ void PIDController::SetTolerance(float percent) { * * @param absTolerance absolute error which is tolerable */ -void PIDController::SetAbsoluteTolerance(float absTolerance) { +void PIDController::SetAbsoluteTolerance(double absTolerance) { std::lock_guard lock(m_mutex); m_toleranceType = kAbsoluteTolerance; m_tolerance = absTolerance; @@ -469,7 +469,7 @@ void PIDController::SetAbsoluteTolerance(float absTolerance) { * * @param percent percentage error which is tolerable */ -void PIDController::SetPercentTolerance(float percent) { +void PIDController::SetPercentTolerance(double percent) { std::lock_guard lock(m_mutex); m_toleranceType = kPercentTolerance; m_tolerance = percent; diff --git a/wpilibc/sim/src/PWM.cpp b/wpilibc/sim/src/PWM.cpp index caa00bfdee..1f905918d6 100644 --- a/wpilibc/sim/src/PWM.cpp +++ b/wpilibc/sim/src/PWM.cpp @@ -14,8 +14,8 @@ using namespace frc; -const float PWM::kDefaultPwmPeriod = 5.05; -const float PWM::kDefaultPwmCenter = 1.5; +const double PWM::kDefaultPwmPeriod = 5.05; +const double PWM::kDefaultPwmCenter = 1.5; const int PWM::kDefaultPwmStepsDown = 1000; const int PWM::kPwmDisabled = 0; @@ -108,7 +108,7 @@ void PWM::SetBounds(double max, double deadbandMax, double center, * * @param pos The position to set the servo between 0.0 and 1.0. */ -void PWM::SetPosition(float pos) { +void PWM::SetPosition(double pos) { if (pos < 0.0) { pos = 0.0; } else if (pos > 1.0) { @@ -128,8 +128,8 @@ void PWM::SetPosition(float pos) { * * @return The position the servo is set to between 0.0 and 1.0. */ -float PWM::GetPosition() const { - float value = impl->Get(); +double PWM::GetPosition() const { + double value = impl->Get(); if (value < 0.0) { return 0.0; } else if (value > 1.0) { @@ -152,7 +152,7 @@ float PWM::GetPosition() const { * * @param speed The speed to set the speed controller between -1.0 and 1.0. */ -void PWM::SetSpeed(float speed) { +void PWM::SetSpeed(double speed) { // clamp speed to be in the range 1.0 >= speed >= -1.0 if (speed < -1.0) { speed = -1.0; @@ -175,8 +175,8 @@ void PWM::SetSpeed(float speed) { * * @return The most recently set speed between -1.0 and 1.0. */ -float PWM::GetSpeed() const { - float value = impl->Get(); +double PWM::GetSpeed() const { + double value = impl->Get(); if (value > 1.0) { return 1.0; } else if (value < -1.0) { diff --git a/wpilibc/sim/src/Relay.cpp b/wpilibc/sim/src/Relay.cpp index 205b4ba482..3fed899ff8 100644 --- a/wpilibc/sim/src/Relay.cpp +++ b/wpilibc/sim/src/Relay.cpp @@ -147,7 +147,7 @@ int Relay::GetChannel() const { return m_channel; } * * @param timeout The timeout (in seconds) for this relay object */ -void Relay::SetExpiration(float timeout) { +void Relay::SetExpiration(double timeout) { m_safetyHelper->SetExpiration(timeout); } @@ -156,7 +156,7 @@ void Relay::SetExpiration(float timeout) { * * @return The expiration time value. */ -float Relay::GetExpiration() const { return m_safetyHelper->GetExpiration(); } +double Relay::GetExpiration() const { return m_safetyHelper->GetExpiration(); } /** * Check if the relay object is currently alive or stopped due to a timeout. diff --git a/wpilibc/sim/src/RobotDrive.cpp b/wpilibc/sim/src/RobotDrive.cpp index 3f48a5225e..7b27a6e097 100644 --- a/wpilibc/sim/src/RobotDrive.cpp +++ b/wpilibc/sim/src/RobotDrive.cpp @@ -208,22 +208,22 @@ RobotDrive::RobotDrive(std::shared_ptr frontLeftMotor, * radius r = -ln(curve)*w for a given value of curve and * wheelbase w. */ -void RobotDrive::Drive(float outputMagnitude, float curve) { - float leftOutput, rightOutput; +void RobotDrive::Drive(double outputMagnitude, double curve) { + double leftOutput, rightOutput; static bool reported = false; if (!reported) { reported = true; } if (curve < 0) { - float value = std::log(-curve); - float ratio = (value - m_sensitivity) / (value + m_sensitivity); + double value = std::log(-curve); + double ratio = (value - m_sensitivity) / (value + m_sensitivity); if (ratio == 0) ratio = .0000000001; leftOutput = outputMagnitude / ratio; rightOutput = outputMagnitude; } else if (curve > 0) { - float value = std::log(curve); - float ratio = (value - m_sensitivity) / (value + m_sensitivity); + double value = std::log(curve); + double ratio = (value - m_sensitivity) / (value + m_sensitivity); if (ratio == 0) ratio = .0000000001; leftOutput = outputMagnitude; rightOutput = outputMagnitude / ratio; @@ -294,7 +294,7 @@ void RobotDrive::TankDrive(GenericHID& leftStick, int leftAxis, * @param leftValue The value of the left stick. * @param rightValue The value of the right stick. */ -void RobotDrive::TankDrive(float leftValue, float rightValue, +void RobotDrive::TankDrive(double leftValue, double rightValue, bool squaredInputs) { static bool reported = false; if (!reported) { @@ -376,8 +376,8 @@ void RobotDrive::ArcadeDrive(GenericHID& stick, bool squaredInputs) { void RobotDrive::ArcadeDrive(GenericHID* moveStick, int moveAxis, GenericHID* rotateStick, int rotateAxis, bool squaredInputs) { - float moveValue = moveStick->GetRawAxis(moveAxis); - float rotateValue = rotateStick->GetRawAxis(rotateAxis); + double moveValue = moveStick->GetRawAxis(moveAxis); + double rotateValue = rotateStick->GetRawAxis(rotateAxis); ArcadeDrive(moveValue, rotateValue, squaredInputs); } @@ -401,8 +401,8 @@ void RobotDrive::ArcadeDrive(GenericHID* moveStick, int moveAxis, void RobotDrive::ArcadeDrive(GenericHID& moveStick, int moveAxis, GenericHID& rotateStick, int rotateAxis, bool squaredInputs) { - float moveValue = moveStick.GetRawAxis(moveAxis); - float rotateValue = rotateStick.GetRawAxis(rotateAxis); + double moveValue = moveStick.GetRawAxis(moveAxis); + double rotateValue = rotateStick.GetRawAxis(rotateAxis); ArcadeDrive(moveValue, rotateValue, squaredInputs); } @@ -416,7 +416,7 @@ void RobotDrive::ArcadeDrive(GenericHID& moveStick, int moveAxis, * @param rotateValue The value to use for the rotate right/left * @param squaredInputs If set, increases the sensitivity at low speeds */ -void RobotDrive::ArcadeDrive(float moveValue, float rotateValue, +void RobotDrive::ArcadeDrive(double moveValue, double rotateValue, bool squaredInputs) { static bool reported = false; if (!reported) { @@ -424,8 +424,8 @@ void RobotDrive::ArcadeDrive(float moveValue, float rotateValue, } // local variables to hold the computed PWM values for the motors - float leftMotorOutput; - float rightMotorOutput; + double leftMotorOutput; + double rightMotorOutput; moveValue = Limit(moveValue); rotateValue = Limit(rotateValue); @@ -485,8 +485,8 @@ void RobotDrive::ArcadeDrive(float moveValue, float rotateValue, * @param gyroAngle The current angle reading from the gyro. Use this to * implement field-oriented controls. */ -void RobotDrive::MecanumDrive_Cartesian(float x, float y, float rotation, - float gyroAngle) { +void RobotDrive::MecanumDrive_Cartesian(double x, double y, double rotation, + double gyroAngle) { static bool reported = false; if (!reported) { reported = true; @@ -535,8 +535,8 @@ void RobotDrive::MecanumDrive_Cartesian(float x, float y, float rotation, * @param rotation The rate of rotation for the robot that is completely * independent of the magnitute or direction. [-1.0..1.0] */ -void RobotDrive::MecanumDrive_Polar(float magnitude, float direction, - float rotation) { +void RobotDrive::MecanumDrive_Polar(double magnitude, double direction, + double rotation) { static bool reported = false; if (!reported) { reported = true; @@ -581,8 +581,8 @@ void RobotDrive::MecanumDrive_Polar(float magnitude, float direction, * @param rotation The rate of rotation for the robot that is completely * independent of the magnitude or direction. [-1.0..1.0] */ -void RobotDrive::HolonomicDrive(float magnitude, float direction, - float rotation) { +void RobotDrive::HolonomicDrive(double magnitude, double direction, + double rotation) { MecanumDrive_Polar(magnitude, direction, rotation); } @@ -596,7 +596,8 @@ void RobotDrive::HolonomicDrive(float magnitude, float direction, * @param leftOutput The speed to send to the left side of the robot. * @param rightOutput The speed to send to the right side of the robot. */ -void RobotDrive::SetLeftRightMotorOutputs(float leftOutput, float rightOutput) { +void RobotDrive::SetLeftRightMotorOutputs(double leftOutput, + double rightOutput) { wpi_assert(m_rearLeftMotor != nullptr && m_rearRightMotor != nullptr); if (m_frontLeftMotor != nullptr) @@ -617,7 +618,7 @@ void RobotDrive::SetLeftRightMotorOutputs(float leftOutput, float rightOutput) { /** * Limit motor values to the -1.0 to +1.0 range. */ -float RobotDrive::Limit(float num) { +double RobotDrive::Limit(double num) { if (num > 1.0) { return 1.0; } @@ -682,7 +683,7 @@ void RobotDrive::SetInvertedMotor(MotorType motor, bool isInverted) { * @param sensitivity Effectively sets the turning sensitivity (or turn radius * for a given value) */ -void RobotDrive::SetSensitivity(float sensitivity) { +void RobotDrive::SetSensitivity(double sensitivity) { m_sensitivity = sensitivity; } @@ -695,11 +696,11 @@ void RobotDrive::SetSensitivity(float sensitivity) { */ void RobotDrive::SetMaxOutput(double maxOutput) { m_maxOutput = maxOutput; } -void RobotDrive::SetExpiration(float timeout) { +void RobotDrive::SetExpiration(double timeout) { // FIXME: m_safetyHelper->SetExpiration(timeout); } -float RobotDrive::GetExpiration() const { +double RobotDrive::GetExpiration() const { return -1; // FIXME: return m_safetyHelper->GetExpiration(); } diff --git a/wpilibc/sim/src/SafePWM.cpp b/wpilibc/sim/src/SafePWM.cpp index ae2a5158fc..e55963d106 100644 --- a/wpilibc/sim/src/SafePWM.cpp +++ b/wpilibc/sim/src/SafePWM.cpp @@ -27,7 +27,7 @@ SafePWM::SafePWM(int channel) : PWM(channel) { * * @param timeout The timeout (in seconds) for this motor object */ -void SafePWM::SetExpiration(float timeout) { +void SafePWM::SetExpiration(double timeout) { m_safetyHelper->SetExpiration(timeout); } @@ -36,7 +36,9 @@ void SafePWM::SetExpiration(float timeout) { * * @returns The expiration time value. */ -float SafePWM::GetExpiration() const { return m_safetyHelper->GetExpiration(); } +double SafePWM::GetExpiration() const { + return m_safetyHelper->GetExpiration(); +} /** * Check if the PWM object is currently alive or stopped due to a timeout. @@ -86,7 +88,7 @@ void SafePWM::GetDescription(std::ostringstream& desc) const { * * @param speed Value to pass to the PWM class */ -void SafePWM::SetSpeed(float speed) { +void SafePWM::SetSpeed(double speed) { PWM::SetSpeed(speed); m_safetyHelper->Feed(); } diff --git a/wpilibc/sim/src/Talon.cpp b/wpilibc/sim/src/Talon.cpp index fc27dca4ff..c4f13735e4 100644 --- a/wpilibc/sim/src/Talon.cpp +++ b/wpilibc/sim/src/Talon.cpp @@ -43,14 +43,14 @@ Talon::Talon(int channel) : SafePWM(channel) { * * @param speed The speed value between -1.0 and 1.0 to set. */ -void Talon::Set(float speed) { SetSpeed(speed); } +void Talon::Set(double speed) { SetSpeed(speed); } /** * Get the recently set value of the PWM. * * @return The most recently set value for the PWM between -1.0 and 1.0. */ -float Talon::Get() const { return GetSpeed(); } +double Talon::Get() const { return GetSpeed(); } /** * Common interface for disabling a motor. @@ -62,4 +62,4 @@ void Talon::Disable() { SetRaw(kPwmDisabled); } * * @param output Write out the PWM value as was found in the PIDController */ -void Talon::PIDWrite(float output) { Set(output); } +void Talon::PIDWrite(double output) { Set(output); } diff --git a/wpilibc/sim/src/Victor.cpp b/wpilibc/sim/src/Victor.cpp index ecc6d9cd38..fa4834dc05 100644 --- a/wpilibc/sim/src/Victor.cpp +++ b/wpilibc/sim/src/Victor.cpp @@ -45,14 +45,14 @@ Victor::Victor(int channel) : SafePWM(channel) { * * @param speed The speed value between -1.0 and 1.0 to set. */ -void Victor::Set(float speed) { SetSpeed(speed); } +void Victor::Set(double speed) { SetSpeed(speed); } /** * Get the recently set value of the PWM. * * @return The most recently set value for the PWM between -1.0 and 1.0. */ -float Victor::Get() const { return GetSpeed(); } +double Victor::Get() const { return GetSpeed(); } /** * Common interface for disabling a motor. @@ -64,4 +64,4 @@ void Victor::Disable() { SetRaw(kPwmDisabled); } * * @param output Write out the PWM value as was found in the PIDController */ -void Victor::PIDWrite(float output) { Set(output); } +void Victor::PIDWrite(double output) { Set(output); } diff --git a/wpilibc/sim/src/XboxController.cpp b/wpilibc/sim/src/XboxController.cpp index 27cc912f66..136d88853b 100644 --- a/wpilibc/sim/src/XboxController.cpp +++ b/wpilibc/sim/src/XboxController.cpp @@ -27,7 +27,7 @@ XboxController::XboxController(int port) * * @param hand Side of controller whose value should be returned. */ -float XboxController::GetX(JoystickHand hand) const { +double XboxController::GetX(JoystickHand hand) const { if (hand == kLeftHand) { return GetRawAxis(0); } else { @@ -40,7 +40,7 @@ float XboxController::GetX(JoystickHand hand) const { * * @param hand Side of controller whose value should be returned. */ -float XboxController::GetY(JoystickHand hand) const { +double XboxController::GetY(JoystickHand hand) const { if (hand == kLeftHand) { return GetRawAxis(1); } else { @@ -80,7 +80,7 @@ bool XboxController::GetStickButton(JoystickHand hand) const { * * @param hand Side of controller whose value should be returned. */ -float XboxController::GetTriggerAxis(JoystickHand hand) const { +double XboxController::GetTriggerAxis(JoystickHand hand) const { if (hand == kLeftHand) { return GetRawAxis(2); } else { diff --git a/wpilibc/sim/src/simulation/SimContinuousOutput.cpp b/wpilibc/sim/src/simulation/SimContinuousOutput.cpp index 225dea6955..0e3e80331a 100644 --- a/wpilibc/sim/src/simulation/SimContinuousOutput.cpp +++ b/wpilibc/sim/src/simulation/SimContinuousOutput.cpp @@ -16,10 +16,10 @@ SimContinuousOutput::SimContinuousOutput(std::string topic) { std::cout << "Initialized ~/simulator/" + topic << std::endl; } -void SimContinuousOutput::Set(float speed) { +void SimContinuousOutput::Set(double speed) { gazebo::msgs::Float64 msg; msg.set_data(speed); pub->Publish(msg); } -float SimContinuousOutput::Get() { return speed; } +double SimContinuousOutput::Get() { return speed; } diff --git a/wpilibcIntegrationTests/src/AnalogLoopTest.cpp b/wpilibcIntegrationTests/src/AnalogLoopTest.cpp index 92a52b8b38..27929c73ff 100644 --- a/wpilibcIntegrationTests/src/AnalogLoopTest.cpp +++ b/wpilibcIntegrationTests/src/AnalogLoopTest.cpp @@ -43,11 +43,11 @@ class AnalogLoopTest : public testing::Test { TEST_F(AnalogLoopTest, AnalogInputWorks) { // Set the output voltage and check if the input measures the same voltage for (int32_t i = 0; i < 50; i++) { - m_output->SetVoltage(i / 10.0f); + m_output->SetVoltage(i / 10.0); Wait(kDelayTime); - EXPECT_NEAR(m_output->GetVoltage(), m_input->GetVoltage(), 0.01f); + EXPECT_NEAR(m_output->GetVoltage(), m_input->GetVoltage(), 0.01); } } @@ -57,23 +57,23 @@ TEST_F(AnalogLoopTest, AnalogInputWorks) { */ TEST_F(AnalogLoopTest, AnalogTriggerWorks) { AnalogTrigger trigger(m_input); - trigger.SetLimitsVoltage(2.0f, 3.0f); + trigger.SetLimitsVoltage(2.0, 3.0); - m_output->SetVoltage(1.0f); + m_output->SetVoltage(1.0); Wait(kDelayTime); EXPECT_FALSE(trigger.GetInWindow()) << "Analog trigger is in the window (2V, 3V)"; EXPECT_FALSE(trigger.GetTriggerState()) << "Analog trigger is on"; - m_output->SetVoltage(2.5f); + m_output->SetVoltage(2.5); Wait(kDelayTime); EXPECT_TRUE(trigger.GetInWindow()) << "Analog trigger is not in the window (2V, 3V)"; EXPECT_FALSE(trigger.GetTriggerState()) << "Analog trigger is on"; - m_output->SetVoltage(4.0f); + m_output->SetVoltage(4.0); Wait(kDelayTime); EXPECT_FALSE(trigger.GetInWindow()) @@ -87,7 +87,7 @@ TEST_F(AnalogLoopTest, AnalogTriggerWorks) { */ TEST_F(AnalogLoopTest, AnalogTriggerCounterWorks) { AnalogTrigger trigger(m_input); - trigger.SetLimitsVoltage(2.0f, 3.0f); + trigger.SetLimitsVoltage(2.0, 3.0); Counter counter(trigger); @@ -111,7 +111,7 @@ static void InterruptHandler(uint32_t interruptAssertedMask, void* param) { TEST_F(AnalogLoopTest, AsynchronusInterruptWorks) { int32_t param = 0; AnalogTrigger trigger(m_input); - trigger.SetLimitsVoltage(2.0f, 3.0f); + trigger.SetLimitsVoltage(2.0, 3.0); // Given an interrupt handler that sets an int32_t to 12345 std::shared_ptr triggerOutput = diff --git a/wpilibcIntegrationTests/src/CounterTest.cpp b/wpilibcIntegrationTests/src/CounterTest.cpp index a5d6dbba05..c80996d0f5 100644 --- a/wpilibcIntegrationTests/src/CounterTest.cpp +++ b/wpilibcIntegrationTests/src/CounterTest.cpp @@ -51,9 +51,9 @@ class CounterTest : public testing::Test { m_talonCounter->Reset(); m_victorCounter->Reset(); m_jaguarCounter->Reset(); - m_talon->Set(0.0f); - m_victor->Set(0.0f); - m_jaguar->Set(0.0f); + m_talon->Set(0.0); + m_victor->Set(0.0); + m_jaguar->Set(0.0); } }; @@ -64,44 +64,44 @@ class CounterTest : public testing::Test { TEST_F(CounterTest, CountTalon) { Reset(); /* Run the motor forward and determine if the counter is counting. */ - m_talon->Set(1.0f); + m_talon->Set(1.0); Wait(0.5); - EXPECT_NE(0.0f, m_talonCounter->Get()) << "The counter did not count (talon)"; + EXPECT_NE(0.0, m_talonCounter->Get()) << "The counter did not count (talon)"; /* Set the motor to 0 and determine if the counter resets to 0. */ - m_talon->Set(0.0f); + m_talon->Set(0.0); Wait(0.5); m_talonCounter->Reset(); - EXPECT_FLOAT_EQ(0.0f, m_talonCounter->Get()) + EXPECT_FLOAT_EQ(0.0, m_talonCounter->Get()) << "The counter did not restart to 0 (talon)"; } TEST_F(CounterTest, CountVictor) { Reset(); /* Run the motor forward and determine if the counter is counting. */ - m_victor->Set(1.0f); + m_victor->Set(1.0); Wait(0.5); - EXPECT_NE(0.0f, m_victorCounter->Get()) + EXPECT_NE(0.0, m_victorCounter->Get()) << "The counter did not count (victor)"; /* Set the motor to 0 and determine if the counter resets to 0. */ - m_victor->Set(0.0f); + m_victor->Set(0.0); Wait(0.5); m_victorCounter->Reset(); - EXPECT_FLOAT_EQ(0.0f, m_victorCounter->Get()) + EXPECT_FLOAT_EQ(0.0, m_victorCounter->Get()) << "The counter did not restart to 0 (jaguar)"; } TEST_F(CounterTest, CountJaguar) { Reset(); /* Run the motor forward and determine if the counter is counting. */ - m_jaguar->Set(1.0f); + m_jaguar->Set(1.0); Wait(0.5); - EXPECT_NE(0.0f, m_jaguarCounter->Get()) + EXPECT_NE(0.0, m_jaguarCounter->Get()) << "The counter did not count (jaguar)"; /* Set the motor to 0 and determine if the counter resets to 0. */ - m_jaguar->Set(0.0f); + m_jaguar->Set(0.0); Wait(0.5); m_jaguarCounter->Reset(); - EXPECT_FLOAT_EQ(0.0f, m_jaguarCounter->Get()) + EXPECT_FLOAT_EQ(0.0, m_jaguarCounter->Get()) << "The counter did not restart to 0 (jaguar)"; } @@ -113,11 +113,11 @@ TEST_F(CounterTest, TalonGetStopped) { Reset(); /* Set the Max Period of the counter and run the motor */ m_talonCounter->SetMaxPeriod(kMaxPeriod); - m_talon->Set(1.0f); + m_talon->Set(1.0); Wait(0.5); EXPECT_FALSE(m_talonCounter->GetStopped()) << "The counter did not count."; /* Stop the motor and wait until the Max Period is exceeded */ - m_talon->Set(0.0f); + m_talon->Set(0.0); Wait(kMotorDelay); EXPECT_TRUE(m_talonCounter->GetStopped()) << "The counter did not stop counting."; @@ -127,11 +127,11 @@ TEST_F(CounterTest, VictorGetStopped) { Reset(); /* Set the Max Period of the counter and run the motor */ m_victorCounter->SetMaxPeriod(kMaxPeriod); - m_victor->Set(1.0f); + m_victor->Set(1.0); Wait(0.5); EXPECT_FALSE(m_victorCounter->GetStopped()) << "The counter did not count."; /* Stop the motor and wait until the Max Period is exceeded */ - m_victor->Set(0.0f); + m_victor->Set(0.0); Wait(kMotorDelay); EXPECT_TRUE(m_victorCounter->GetStopped()) << "The counter did not stop counting."; @@ -141,11 +141,11 @@ TEST_F(CounterTest, JaguarGetStopped) { Reset(); /* Set the Max Period of the counter and run the motor */ m_jaguarCounter->SetMaxPeriod(kMaxPeriod); - m_jaguar->Set(1.0f); + m_jaguar->Set(1.0); Wait(0.5); EXPECT_FALSE(m_jaguarCounter->GetStopped()) << "The counter did not count."; /* Stop the motor and wait until the Max Period is exceeded */ - m_jaguar->Set(0.0f); + m_jaguar->Set(0.0); Wait(kMotorDelay); EXPECT_TRUE(m_jaguarCounter->GetStopped()) << "The counter did not stop counting."; diff --git a/wpilibcIntegrationTests/src/FakeEncoderTest.cpp b/wpilibcIntegrationTests/src/FakeEncoderTest.cpp index b8fc42af9b..50519b4849 100644 --- a/wpilibcIntegrationTests/src/FakeEncoderTest.cpp +++ b/wpilibcIntegrationTests/src/FakeEncoderTest.cpp @@ -83,7 +83,7 @@ class FakeEncoderTest : public testing::Test { * Test the encoder by reseting it to 0 and reading the value. */ TEST_F(FakeEncoderTest, TestDefaultState) { - EXPECT_FLOAT_EQ(0.0f, m_encoder->Get()) << "The encoder did not start at 0."; + EXPECT_FLOAT_EQ(0.0, m_encoder->Get()) << "The encoder did not start at 0."; } /** @@ -93,7 +93,7 @@ TEST_F(FakeEncoderTest, TestCountUp) { m_encoder->Reset(); Simulate100QuadratureTicks(); - EXPECT_FLOAT_EQ(100.0f, m_encoder->Get()) << "Encoder did not count to 100."; + EXPECT_FLOAT_EQ(100.0, m_encoder->Get()) << "Encoder did not count to 100."; } /** diff --git a/wpilibcIntegrationTests/src/MotorEncoderTest.cpp b/wpilibcIntegrationTests/src/MotorEncoderTest.cpp index 8d0e5c2336..0c0c486080 100644 --- a/wpilibcIntegrationTests/src/MotorEncoderTest.cpp +++ b/wpilibcIntegrationTests/src/MotorEncoderTest.cpp @@ -73,7 +73,7 @@ class MotorEncoderTest : public testing::TestWithParam { } void Reset() { - m_speedController->Set(0.0f); + m_speedController->Set(0.0); m_encoder->Reset(); } }; @@ -101,12 +101,12 @@ TEST_P(MotorEncoderTest, Decrement) { Reset(); /* Drive the speed controller briefly to move the encoder */ - m_speedController->Set(-0.2f); + m_speedController->Set(-0.2); Wait(kMotorTime); - m_speedController->Set(0.0f); + m_speedController->Set(0.0); /* The encoder should be positive now */ - EXPECT_LT(m_encoder->Get(), 0.0f) + EXPECT_LT(m_encoder->Get(), 0.0) << "Encoder should have decremented after the motor moved"; } @@ -116,15 +116,15 @@ TEST_P(MotorEncoderTest, Decrement) { TEST_P(MotorEncoderTest, ClampSpeed) { Reset(); - m_speedController->Set(2.0f); + m_speedController->Set(2.0); Wait(kMotorTime); - EXPECT_FLOAT_EQ(1.0f, m_speedController->Get()); + EXPECT_FLOAT_EQ(1.0, m_speedController->Get()); - m_speedController->Set(-2.0f); + m_speedController->Set(-2.0); Wait(kMotorTime); - EXPECT_FLOAT_EQ(-1.0f, m_speedController->Get()); + EXPECT_FLOAT_EQ(-1.0, m_speedController->Get()); } /** @@ -134,9 +134,9 @@ TEST_P(MotorEncoderTest, PositionPIDController) { Reset(); double goal = 1000; m_encoder->SetPIDSourceType(PIDSourceType::kDisplacement); - PIDController pid(0.001f, 0.0005f, 0.0f, m_encoder, m_speedController); - pid.SetAbsoluteTolerance(50.0f); - pid.SetOutputRange(-0.2f, 0.2f); + PIDController pid(0.001, 0.0005, 0.0, m_encoder, m_speedController); + pid.SetAbsoluteTolerance(50.0); + pid.SetOutputRange(-0.2, 0.2); pid.SetSetpoint(goal); /* 10 seconds should be plenty time to get to the setpoint */ @@ -158,10 +158,10 @@ TEST_P(MotorEncoderTest, VelocityPIDController) { Reset(); m_encoder->SetPIDSourceType(PIDSourceType::kRate); - PIDController pid(1e-5, 0.0f, 3e-5, 8e-5, m_encoder, m_speedController); - pid.SetAbsoluteTolerance(200.0f); + PIDController pid(1e-5, 0.0, 3e-5, 8e-5, m_encoder, m_speedController); + pid.SetAbsoluteTolerance(200.0); pid.SetToleranceBuffer(50); - pid.SetOutputRange(-0.3f, 0.3f); + pid.SetOutputRange(-0.3, 0.3); pid.SetSetpoint(600); /* 10 seconds should be plenty time to get to the setpoint */ diff --git a/wpilibcIntegrationTests/src/MotorInvertingTest.cpp b/wpilibcIntegrationTests/src/MotorInvertingTest.cpp index d3d01b3399..4f0b858484 100644 --- a/wpilibcIntegrationTests/src/MotorInvertingTest.cpp +++ b/wpilibcIntegrationTests/src/MotorInvertingTest.cpp @@ -66,7 +66,7 @@ class MotorInvertingTest void Reset() { m_speedController->SetInverted(false); - m_speedController->Set(0.0f); + m_speedController->Set(0.0); m_encoder->Reset(); } }; diff --git a/wpilibcIntegrationTests/src/PIDToleranceTest.cpp b/wpilibcIntegrationTests/src/PIDToleranceTest.cpp index 0bf227d3b6..8f069c12b4 100644 --- a/wpilibcIntegrationTests/src/PIDToleranceTest.cpp +++ b/wpilibcIntegrationTests/src/PIDToleranceTest.cpp @@ -27,7 +27,7 @@ class PIDToleranceTest : public testing::Test { double PIDGet() { return val; } }; class fakeOutput : public PIDOutput { - void PIDWrite(float output) {} + void PIDWrite(double output) {} }; fakeInput inp; fakeOutput out; diff --git a/wpilibcIntegrationTests/src/TiltPanCameraTest.cpp b/wpilibcIntegrationTests/src/TiltPanCameraTest.cpp index d86b1e1171..914a74695e 100644 --- a/wpilibcIntegrationTests/src/TiltPanCameraTest.cpp +++ b/wpilibcIntegrationTests/src/TiltPanCameraTest.cpp @@ -51,7 +51,7 @@ class TiltPanCameraTest : public testing::Test { m_spiAccel = new ADXL345_SPI(SPI::kOnboardCS1); m_tilt->Set(kTiltSetpoint45); - m_pan->SetAngle(0.0f); + m_pan->SetAngle(0.0); Wait(kServoResetTime); @@ -75,7 +75,7 @@ AnalogGyro* TiltPanCameraTest::m_gyro = nullptr; * Test if the gyro angle defaults to 0 immediately after being reset. */ void TiltPanCameraTest::DefaultGyroAngle() { - EXPECT_NEAR(0.0f, m_gyro->GetAngle(), 1.0f); + EXPECT_NEAR(0.0, m_gyro->GetAngle(), 1.0); } /** @@ -109,7 +109,7 @@ void TiltPanCameraTest::GyroAngle() { */ void TiltPanCameraTest::GyroCalibratedParameters() { uint32_t cCenter = m_gyro->GetCenter(); - float cOffset = m_gyro->GetOffset(); + double cOffset = m_gyro->GetOffset(); delete m_gyro; m_gyro = new AnalogGyro(TestBench::kCameraGyroChannel, cCenter, cOffset); m_gyro->SetSensitivity(kSensitivity); @@ -117,8 +117,8 @@ void TiltPanCameraTest::GyroCalibratedParameters() { // Default gyro angle test // Accumulator needs a small amount of time to reset before being tested m_gyro->Reset(); - Wait(.001); - EXPECT_NEAR(0.0f, m_gyro->GetAngle(), 1.0f); + Wait(0.001); + EXPECT_NEAR(0.0, m_gyro->GetAngle(), 1.0); // Gyro angle test // Make sure that the gyro doesn't get jerked when the servo goes to zero. diff --git a/wpilibj/src/athena/cpp/lib/AnalogGyroJNI.cpp b/wpilibj/src/athena/cpp/lib/AnalogGyroJNI.cpp index 6a9f294131..f5e019f872 100644 --- a/wpilibj/src/athena/cpp/lib/AnalogGyroJNI.cpp +++ b/wpilibj/src/athena/cpp/lib/AnalogGyroJNI.cpp @@ -75,10 +75,10 @@ JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_AnalogGyroJNI_freeAnalogGy /* * Class: edu_wpi_first_wpilibj_hal_AnalogGyroJNI * Method: setAnalogGyroParameters - * Signature: (IFFI)V + * Signature: (IDDI)V */ JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_AnalogGyroJNI_setAnalogGyroParameters( - JNIEnv* env, jclass, jint id, jfloat vPDPS, jfloat offset, jint center) { + JNIEnv* env, jclass, jint id, jdouble vPDPS, jdouble offset, jint center) { ANALOGGYROJNI_LOG(logDEBUG) << "Calling ANALOGGYROJNI setAnalogGyroParameters"; ANALOGGYROJNI_LOG(logDEBUG) << "Gyro Handle = " << (HAL_GyroHandle)id; int32_t status = 0; @@ -90,10 +90,10 @@ JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_AnalogGyroJNI_setAnalogGyr /* * Class: edu_wpi_first_wpilibj_hal_AnalogGyroJNI * Method: setAnalogGyroVoltsPerDegreePerSecond - * Signature: (IF)V + * Signature: (ID)V */ JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_AnalogGyroJNI_setAnalogGyroVoltsPerDegreePerSecond( - JNIEnv* env, jclass, jint id, jfloat vPDPS) { + JNIEnv* env, jclass, jint id, jdouble vPDPS) { ANALOGGYROJNI_LOG(logDEBUG) << "Calling ANALOGGYROJNI setAnalogGyroVoltsPerDegreePerSecond"; ANALOGGYROJNI_LOG(logDEBUG) << "Gyro Handle = " << (HAL_GyroHandle)id; ANALOGGYROJNI_LOG(logDEBUG) << "vPDPS = " << vPDPS; @@ -136,10 +136,10 @@ JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_AnalogGyroJNI_calibrateAna /* * Class: edu_wpi_first_wpilibj_hal_AnalogGyroJNI * Method: setAnalogGyroDeadband - * Signature: (IF)V + * Signature: (ID)V */ JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_AnalogGyroJNI_setAnalogGyroDeadband( - JNIEnv* env, jclass, jint id, jfloat deadband) { + JNIEnv* env, jclass, jint id, jdouble deadband) { ANALOGGYROJNI_LOG(logDEBUG) << "Calling ANALOGGYROJNI setAnalogGyroDeadband"; ANALOGGYROJNI_LOG(logDEBUG) << "Gyro Handle = " << (HAL_GyroHandle)id; int32_t status = 0; @@ -151,14 +151,14 @@ JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_AnalogGyroJNI_setAnalogGyr /* * Class: edu_wpi_first_wpilibj_hal_AnalogGyroJNI * Method: getAnalogGyroAngle - * Signature: (I)F + * Signature: (I)D */ -JNIEXPORT jfloat JNICALL Java_edu_wpi_first_wpilibj_hal_AnalogGyroJNI_getAnalogGyroAngle( +JNIEXPORT jdouble JNICALL Java_edu_wpi_first_wpilibj_hal_AnalogGyroJNI_getAnalogGyroAngle( JNIEnv* env, jclass, jint id) { ANALOGGYROJNI_LOG(logDEBUG) << "Calling ANALOGGYROJNI getAnalogGyroAngle"; ANALOGGYROJNI_LOG(logDEBUG) << "Gyro Handle = " << (HAL_GyroHandle)id; int32_t status = 0; - jfloat value = HAL_GetAnalogGyroAngle((HAL_GyroHandle)id, &status); + jdouble value = HAL_GetAnalogGyroAngle((HAL_GyroHandle)id, &status); ANALOGGYROJNI_LOG(logDEBUG) << "Status = " << status; ANALOGGYROJNI_LOG(logDEBUG) << "Result = " << value; CheckStatus(env, status); @@ -185,14 +185,14 @@ JNIEXPORT jdouble JNICALL Java_edu_wpi_first_wpilibj_hal_AnalogGyroJNI_getAnalog /* * Class: edu_wpi_first_wpilibj_hal_AnalogGyroJNI * Method: getAnalogGyroOffset - * Signature: (I)F + * Signature: (I)D */ -JNIEXPORT jfloat JNICALL Java_edu_wpi_first_wpilibj_hal_AnalogGyroJNI_getAnalogGyroOffset( +JNIEXPORT jdouble JNICALL Java_edu_wpi_first_wpilibj_hal_AnalogGyroJNI_getAnalogGyroOffset( JNIEnv* env, jclass, jint id) { ANALOGGYROJNI_LOG(logDEBUG) << "Calling ANALOGGYROJNI getAnalogGyroOffset"; ANALOGGYROJNI_LOG(logDEBUG) << "Gyro Handle = " << (HAL_GyroHandle)id; int32_t status = 0; - jfloat value = HAL_GetAnalogGyroOffset((HAL_GyroHandle)id, &status); + jdouble value = HAL_GetAnalogGyroOffset((HAL_GyroHandle)id, &status); ANALOGGYROJNI_LOG(logDEBUG) << "Status = " << status; ANALOGGYROJNI_LOG(logDEBUG) << "Result = " << value; CheckStatus(env, status); diff --git a/wpilibj/src/athena/cpp/lib/CompressorJNI.cpp b/wpilibj/src/athena/cpp/lib/CompressorJNI.cpp index cf41232448..a77edc44a7 100644 --- a/wpilibj/src/athena/cpp/lib/CompressorJNI.cpp +++ b/wpilibj/src/athena/cpp/lib/CompressorJNI.cpp @@ -98,13 +98,13 @@ Java_edu_wpi_first_wpilibj_hal_CompressorJNI_getCompressorPressureSwitch( /* * Class: edu_wpi_first_wpilibj_hal_CompressorJNI * Method: getCompressorCurrent - * Signature: (J)F + * Signature: (J)D */ -JNIEXPORT jfloat JNICALL +JNIEXPORT jdouble JNICALL Java_edu_wpi_first_wpilibj_hal_CompressorJNI_getCompressorCurrent( JNIEnv *env, jclass, jint compressorHandle) { int32_t status = 0; - float val = HAL_GetCompressorCurrent((HAL_CompressorHandle)compressorHandle, &status); + double val = HAL_GetCompressorCurrent((HAL_CompressorHandle)compressorHandle, &status); CheckStatus(env, status); return val; } diff --git a/wpilibj/src/athena/cpp/lib/HAL.cpp b/wpilibj/src/athena/cpp/lib/HAL.cpp index 162e317e02..f93aa76766 100644 --- a/wpilibj/src/athena/cpp/lib/HAL.cpp +++ b/wpilibj/src/athena/cpp/lib/HAL.cpp @@ -287,9 +287,9 @@ Java_edu_wpi_first_wpilibj_hal_HAL_waitForDSData(JNIEnv* env, jclass) { /* * Class: edu_wpi_first_wpilibj_hal_HAL * Method: HAL_GetMatchTime - * Signature: ()F + * Signature: ()D */ -JNIEXPORT jfloat JNICALL +JNIEXPORT jdouble JNICALL Java_edu_wpi_first_wpilibj_hal_HAL_getMatchTime(JNIEnv* env, jclass) { int32_t status = 0; return HAL_GetMatchTime(&status); diff --git a/wpilibj/src/athena/cpp/lib/PWMJNI.cpp b/wpilibj/src/athena/cpp/lib/PWMJNI.cpp index 5965891ec1..2176785bf0 100644 --- a/wpilibj/src/athena/cpp/lib/PWMJNI.cpp +++ b/wpilibj/src/athena/cpp/lib/PWMJNI.cpp @@ -176,10 +176,10 @@ JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_PWMJNI_setPWMRaw( /* * Class: edu_wpi_first_wpilibj_hal_PWMJNI * Method: setPWMSpeed - * Signature: (IF)V + * Signature: (ID)V */ JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_PWMJNI_setPWMSpeed( - JNIEnv* env, jclass, jint id, jfloat value) { + JNIEnv* env, jclass, jint id, jdouble value) { PWMJNI_LOG(logDEBUG) << "PWM Handle = " << (HAL_DigitalHandle)id; PWMJNI_LOG(logDEBUG) << "PWM Value = " << value; int32_t status = 0; @@ -191,10 +191,10 @@ JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_PWMJNI_setPWMSpeed( /* * Class: edu_wpi_first_wpilibj_hal_PWMJNI * Method: setPWMPosition - * Signature: (IF)V + * Signature: (ID)V */ JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_PWMJNI_setPWMPosition( - JNIEnv* env, jclass, jint id, jfloat value) { + JNIEnv* env, jclass, jint id, jdouble value) { PWMJNI_LOG(logDEBUG) << "PWM Handle = " << (HAL_DigitalHandle)id; PWMJNI_LOG(logDEBUG) << "PWM Value = " << value; int32_t status = 0; @@ -223,14 +223,14 @@ Java_edu_wpi_first_wpilibj_hal_PWMJNI_getPWMRaw( /* * Class: edu_wpi_first_wpilibj_hal_PWMJNI * Method: getPWMSpeed - * Signature: (I)F + * Signature: (I)D */ -JNIEXPORT jfloat JNICALL +JNIEXPORT jdouble JNICALL Java_edu_wpi_first_wpilibj_hal_PWMJNI_getPWMSpeed( JNIEnv* env, jclass, jint id) { PWMJNI_LOG(logDEBUG) << "PWM Handle = " << (HAL_DigitalHandle)id; int32_t status = 0; - jfloat returnValue = HAL_GetPWMSpeed((HAL_DigitalHandle)id, &status); + jdouble returnValue = HAL_GetPWMSpeed((HAL_DigitalHandle)id, &status); PWMJNI_LOG(logDEBUG) << "Status = " << status; PWMJNI_LOG(logDEBUG) << "Value = " << returnValue; CheckStatus(env, status); @@ -240,14 +240,14 @@ Java_edu_wpi_first_wpilibj_hal_PWMJNI_getPWMSpeed( /* * Class: edu_wpi_first_wpilibj_hal_PWMJNI * Method: getPWMPosition - * Signature: (I)F + * Signature: (I)D */ -JNIEXPORT jfloat JNICALL +JNIEXPORT jdouble JNICALL Java_edu_wpi_first_wpilibj_hal_PWMJNI_getPWMPosition( JNIEnv* env, jclass, jint id) { PWMJNI_LOG(logDEBUG) << "PWM Handle = " << (HAL_DigitalHandle)id; int32_t status = 0; - jfloat returnValue = HAL_GetPWMPosition((HAL_DigitalHandle)id, &status); + jdouble returnValue = HAL_GetPWMPosition((HAL_DigitalHandle)id, &status); PWMJNI_LOG(logDEBUG) << "Status = " << status; PWMJNI_LOG(logDEBUG) << "Value = " << returnValue; CheckStatus(env, status); diff --git a/wpilibj/src/athena/cpp/lib/PowerJNI.cpp b/wpilibj/src/athena/cpp/lib/PowerJNI.cpp index f18174a78a..85f6c16510 100644 --- a/wpilibj/src/athena/cpp/lib/PowerJNI.cpp +++ b/wpilibj/src/athena/cpp/lib/PowerJNI.cpp @@ -17,12 +17,12 @@ extern "C" { /* * Class: edu_wpi_first_wpilibj_hal_PowerJNI * Method: getVinVoltage - * Signature: ()F + * Signature: ()D */ -JNIEXPORT jfloat JNICALL +JNIEXPORT jdouble JNICALL Java_edu_wpi_first_wpilibj_hal_PowerJNI_getVinVoltage(JNIEnv* env, jclass) { int32_t status = 0; - float val = HAL_GetVinVoltage(&status); + double val = HAL_GetVinVoltage(&status); CheckStatus(env, status); return val; } @@ -30,12 +30,12 @@ Java_edu_wpi_first_wpilibj_hal_PowerJNI_getVinVoltage(JNIEnv* env, jclass) { /* * Class: edu_wpi_first_wpilibj_hal_PowerJNI * Method: getVinCurrent - * Signature: ()F + * Signature: ()D */ -JNIEXPORT jfloat JNICALL +JNIEXPORT jdouble JNICALL Java_edu_wpi_first_wpilibj_hal_PowerJNI_getVinCurrent(JNIEnv* env, jclass) { int32_t status = 0; - float val = HAL_GetVinCurrent(&status); + double val = HAL_GetVinCurrent(&status); CheckStatus(env, status); return val; } @@ -43,12 +43,12 @@ Java_edu_wpi_first_wpilibj_hal_PowerJNI_getVinCurrent(JNIEnv* env, jclass) { /* * Class: edu_wpi_first_wpilibj_hal_PowerJNI * Method: getUserVoltage6V - * Signature: ()F + * Signature: ()D */ -JNIEXPORT jfloat JNICALL +JNIEXPORT jdouble JNICALL Java_edu_wpi_first_wpilibj_hal_PowerJNI_getUserVoltage6V(JNIEnv* env, jclass) { int32_t status = 0; - float val = HAL_GetUserVoltage6V(&status); + double val = HAL_GetUserVoltage6V(&status); CheckStatus(env, status); return val; } @@ -56,12 +56,12 @@ Java_edu_wpi_first_wpilibj_hal_PowerJNI_getUserVoltage6V(JNIEnv* env, jclass) { /* * Class: edu_wpi_first_wpilibj_hal_PowerJNI * Method: getUserCurrent6V - * Signature: ()F + * Signature: ()D */ -JNIEXPORT jfloat JNICALL +JNIEXPORT jdouble JNICALL Java_edu_wpi_first_wpilibj_hal_PowerJNI_getUserCurrent6V(JNIEnv* env, jclass) { int32_t status = 0; - float val = HAL_GetUserCurrent6V(&status); + double val = HAL_GetUserCurrent6V(&status); CheckStatus(env, status); return val; } @@ -96,12 +96,12 @@ Java_edu_wpi_first_wpilibj_hal_PowerJNI_getUserCurrentFaults6V( /* * Class: edu_wpi_first_wpilibj_hal_PowerJNI * Method: getUserVoltage5V - * Signature: ()F + * Signature: ()D */ -JNIEXPORT jfloat JNICALL +JNIEXPORT jdouble JNICALL Java_edu_wpi_first_wpilibj_hal_PowerJNI_getUserVoltage5V(JNIEnv* env, jclass) { int32_t status = 0; - float val = HAL_GetUserVoltage5V(&status); + double val = HAL_GetUserVoltage5V(&status); CheckStatus(env, status); return val; } @@ -109,12 +109,12 @@ Java_edu_wpi_first_wpilibj_hal_PowerJNI_getUserVoltage5V(JNIEnv* env, jclass) { /* * Class: edu_wpi_first_wpilibj_hal_PowerJNI * Method: getUserCurrent5V - * Signature: ()F + * Signature: ()D */ -JNIEXPORT jfloat JNICALL +JNIEXPORT jdouble JNICALL Java_edu_wpi_first_wpilibj_hal_PowerJNI_getUserCurrent5V(JNIEnv* env, jclass) { int32_t status = 0; - float val = HAL_GetUserCurrent5V(&status); + double val = HAL_GetUserCurrent5V(&status); CheckStatus(env, status); return val; } @@ -149,12 +149,12 @@ Java_edu_wpi_first_wpilibj_hal_PowerJNI_getUserCurrentFaults5V( /* * Class: edu_wpi_first_wpilibj_hal_PowerJNI * Method: getUserVoltage3V3 - * Signature: ()F + * Signature: ()D */ -JNIEXPORT jfloat JNICALL +JNIEXPORT jdouble JNICALL Java_edu_wpi_first_wpilibj_hal_PowerJNI_getUserVoltage3V3(JNIEnv* env, jclass) { int32_t status = 0; - float val = HAL_GetUserVoltage3V3(&status); + double val = HAL_GetUserVoltage3V3(&status); CheckStatus(env, status); return val; } @@ -162,12 +162,12 @@ Java_edu_wpi_first_wpilibj_hal_PowerJNI_getUserVoltage3V3(JNIEnv* env, jclass) { /* * Class: edu_wpi_first_wpilibj_hal_PowerJNI * Method: getUserCurrent3V3 - * Signature: ()F + * Signature: ()D */ -JNIEXPORT jfloat JNICALL +JNIEXPORT jdouble JNICALL Java_edu_wpi_first_wpilibj_hal_PowerJNI_getUserCurrent3V3(JNIEnv* env, jclass) { int32_t status = 0; - float val = HAL_GetUserCurrent3V3(&status); + double val = HAL_GetUserCurrent3V3(&status); CheckStatus(env, status); return val; } diff --git a/wpilibj/src/athena/cpp/lib/SerialPortJNI.cpp b/wpilibj/src/athena/cpp/lib/SerialPortJNI.cpp index e9938494d0..d857b3fec1 100644 --- a/wpilibj/src/athena/cpp/lib/SerialPortJNI.cpp +++ b/wpilibj/src/athena/cpp/lib/SerialPortJNI.cpp @@ -142,11 +142,11 @@ Java_edu_wpi_first_wpilibj_hal_SerialPortJNI_serialSetFlowControl( /* * Class: edu_wpi_first_wpilibj_hal_SerialPortJNI * Method: serialSetTimeout - * Signature: (BF)V + * Signature: (BD)V */ JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_SerialPortJNI_serialSetTimeout( - JNIEnv* env, jclass, jbyte port, jfloat timeout) { + JNIEnv* env, jclass, jbyte port, jdouble timeout) { SERIALJNI_LOG(logDEBUG) << "Setting Serial Timeout"; SERIALJNI_LOG(logDEBUG) << "Timeout: " << timeout; int32_t status = 0; diff --git a/wpilibj/src/athena/java/edu/wpi/first/wpilibj/AnalogGyro.java b/wpilibj/src/athena/java/edu/wpi/first/wpilibj/AnalogGyro.java index 57c986298b..f8db6b4601 100644 --- a/wpilibj/src/athena/java/edu/wpi/first/wpilibj/AnalogGyro.java +++ b/wpilibj/src/athena/java/edu/wpi/first/wpilibj/AnalogGyro.java @@ -25,7 +25,7 @@ import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable; */ public class AnalogGyro extends GyroBase implements Gyro, PIDSource, LiveWindowSendable { - private static final float kDefaultVoltsPerDegreePerSecond = 0.007f; + private static final double kDefaultVoltsPerDegreePerSecond = 0.007; protected AnalogInput m_analog; private boolean m_channelAllocated = false; @@ -108,7 +108,7 @@ public class AnalogGyro extends GyroBase implements Gyro, PIDSource, LiveWindowS } initGyro(); AnalogGyroJNI.setAnalogGyroParameters(m_gyroHandle, kDefaultVoltsPerDegreePerSecond, - (float)offset, center); + offset, center); reset(); } @@ -174,7 +174,7 @@ public class AnalogGyro extends GyroBase implements Gyro, PIDSource, LiveWindowS */ public void setSensitivity(double voltsPerDegreePerSecond) { AnalogGyroJNI.setAnalogGyroVoltsPerDegreePerSecond(m_gyroHandle, - (float)voltsPerDegreePerSecond); + voltsPerDegreePerSecond); } /** @@ -185,6 +185,6 @@ public class AnalogGyro extends GyroBase implements Gyro, PIDSource, LiveWindowS * @param volts The size of the deadband in volts */ void setDeadband(double volts) { - AnalogGyroJNI.setAnalogGyroDeadband(m_gyroHandle, (float)volts); + AnalogGyroJNI.setAnalogGyroDeadband(m_gyroHandle, volts); } } diff --git a/wpilibj/src/athena/java/edu/wpi/first/wpilibj/AnalogInput.java b/wpilibj/src/athena/java/edu/wpi/first/wpilibj/AnalogInput.java index 534cce2409..0e297a4433 100644 --- a/wpilibj/src/athena/java/edu/wpi/first/wpilibj/AnalogInput.java +++ b/wpilibj/src/athena/java/edu/wpi/first/wpilibj/AnalogInput.java @@ -323,7 +323,7 @@ public class AnalogInput extends SensorBase implements PIDSource, LiveWindowSend * @param samplesPerSecond The number of samples per second. */ public static void setGlobalSampleRate(final double samplesPerSecond) { - AnalogJNI.setAnalogSampleRate((float) samplesPerSecond); + AnalogJNI.setAnalogSampleRate(samplesPerSecond); } /** diff --git a/wpilibj/src/athena/java/edu/wpi/first/wpilibj/Compressor.java b/wpilibj/src/athena/java/edu/wpi/first/wpilibj/Compressor.java index b897bb02e9..64df63344f 100644 --- a/wpilibj/src/athena/java/edu/wpi/first/wpilibj/Compressor.java +++ b/wpilibj/src/athena/java/edu/wpi/first/wpilibj/Compressor.java @@ -94,7 +94,7 @@ public class Compressor extends SensorBase implements LiveWindowSendable { * * @return current consumed by the compressor in amps */ - public float getCompressorCurrent() { + public double getCompressorCurrent() { return CompressorJNI.getCompressorCurrent(m_compressorHandle); } diff --git a/wpilibj/src/athena/java/edu/wpi/first/wpilibj/DigitalOutput.java b/wpilibj/src/athena/java/edu/wpi/first/wpilibj/DigitalOutput.java index 18c2c3435a..d54bbd1520 100644 --- a/wpilibj/src/athena/java/edu/wpi/first/wpilibj/DigitalOutput.java +++ b/wpilibj/src/athena/java/edu/wpi/first/wpilibj/DigitalOutput.java @@ -88,7 +88,7 @@ public class DigitalOutput extends DigitalSource implements LiveWindowSendable { * @param channel The channel to pulse. * @param pulseLength The length of the pulse. */ - public void pulse(final int channel, final float pulseLength) { + public void pulse(final int channel, final double pulseLength) { DIOJNI.pulse(m_handle, pulseLength); } @@ -100,10 +100,9 @@ public class DigitalOutput extends DigitalSource implements LiveWindowSendable { */ @Deprecated public void pulse(final int channel, final int pulseLength) { - float convertedPulse = - (float) (pulseLength / 1.0e9 * (DIOJNI.getLoopTiming() * 25)); + double convertedPulse = pulseLength / 1.0e9 * (DIOJNI.getLoopTiming() * 25); System.err - .println("You should use the float version of pulse for portability. This is deprecated"); + .println("You should use the double version of pulse for portability. This is deprecated"); DIOJNI.pulse(m_handle, convertedPulse); } diff --git a/wpilibj/src/athena/java/edu/wpi/first/wpilibj/PWM.java b/wpilibj/src/athena/java/edu/wpi/first/wpilibj/PWM.java index a17604eb5f..1af7bc28ec 100644 --- a/wpilibj/src/athena/java/edu/wpi/first/wpilibj/PWM.java +++ b/wpilibj/src/athena/java/edu/wpi/first/wpilibj/PWM.java @@ -156,7 +156,7 @@ public class PWM extends SensorBase implements LiveWindowSendable { * @pre SetMinNegativePwm() called. */ public void setPosition(double pos) { - PWMJNI.setPWMPosition(m_handle, (float)pos); + PWMJNI.setPWMPosition(m_handle, pos); } /** @@ -185,7 +185,7 @@ public class PWM extends SensorBase implements LiveWindowSendable { * @pre SetMinNegativePwm() called. */ public void setSpeed(double speed) { - PWMJNI.setPWMSpeed(m_handle, (float)speed); + PWMJNI.setPWMSpeed(m_handle, speed); } /** diff --git a/wpilibj/src/athena/java/edu/wpi/first/wpilibj/RobotDrive.java b/wpilibj/src/athena/java/edu/wpi/first/wpilibj/RobotDrive.java index 2665bbb4e1..4d76c32337 100644 --- a/wpilibj/src/athena/java/edu/wpi/first/wpilibj/RobotDrive.java +++ b/wpilibj/src/athena/java/edu/wpi/first/wpilibj/RobotDrive.java @@ -545,7 +545,7 @@ public class RobotDrive implements MotorSafety { * @param rotation The rate of rotation for the robot that is completely independent of the * magnitute or direction. [-1.0..1.0] */ - void holonomicDrive(float magnitude, float direction, float rotation) { + void holonomicDrive(double magnitude, double direction, double rotation) { mecanumDrive_Polar(magnitude, direction, rotation); } diff --git a/wpilibj/src/athena/java/edu/wpi/first/wpilibj/SerialPort.java b/wpilibj/src/athena/java/edu/wpi/first/wpilibj/SerialPort.java index be04177f90..6b36eae823 100644 --- a/wpilibj/src/athena/java/edu/wpi/first/wpilibj/SerialPort.java +++ b/wpilibj/src/athena/java/edu/wpi/first/wpilibj/SerialPort.java @@ -119,7 +119,7 @@ public class SerialPort { setReadBufferSize(1); // Set the default timeout to 5 seconds. - setTimeout(5.0f); + setTimeout(5.0); // Don't wait until the buffer is full to transmit. setWriteBufferMode(WriteBufferMode.kFlushOnAccess); @@ -291,7 +291,7 @@ public class SerialPort { * @param timeout The number of seconds to to wait for I/O. */ public void setTimeout(double timeout) { - SerialPortJNI.serialSetTimeout(m_port, (float) timeout); + SerialPortJNI.serialSetTimeout(m_port, timeout); } /** diff --git a/wpilibj/src/athena/java/edu/wpi/first/wpilibj/Ultrasonic.java b/wpilibj/src/athena/java/edu/wpi/first/wpilibj/Ultrasonic.java index 1a028bb18d..55f7525273 100644 --- a/wpilibj/src/athena/java/edu/wpi/first/wpilibj/Ultrasonic.java +++ b/wpilibj/src/athena/java/edu/wpi/first/wpilibj/Ultrasonic.java @@ -84,7 +84,7 @@ public class Ultrasonic extends SensorBase implements PIDSource, LiveWindowSenda } if (ultrasonic.isEnabled()) { // Do the ping - ultrasonic.m_pingChannel.pulse(m_pingChannel.getChannel(), (float) kPingTime); + ultrasonic.m_pingChannel.pulse(m_pingChannel.getChannel(), kPingTime); } ultrasonic = ultrasonic.m_nextSensor; Timer.delay(.1); // wait for ping to return @@ -288,7 +288,7 @@ public class Ultrasonic extends SensorBase implements PIDSource, LiveWindowSenda // single sensor m_counter.reset(); // reset the counter to zero (invalid data now) // do the ping to start getting a single range - m_pingChannel.pulse(m_pingChannel.getChannel(), (float) kPingTime); + m_pingChannel.pulse(m_pingChannel.getChannel(), kPingTime); } /** diff --git a/wpilibj/src/athena/java/edu/wpi/first/wpilibj/hal/AnalogGyroJNI.java b/wpilibj/src/athena/java/edu/wpi/first/wpilibj/hal/AnalogGyroJNI.java index dcf0686f0a..53b2d3e4c4 100644 --- a/wpilibj/src/athena/java/edu/wpi/first/wpilibj/hal/AnalogGyroJNI.java +++ b/wpilibj/src/athena/java/edu/wpi/first/wpilibj/hal/AnalogGyroJNI.java @@ -15,23 +15,23 @@ public class AnalogGyroJNI extends JNIWrapper { public static native void freeAnalogGyro(int handle); public static native void setAnalogGyroParameters(int handle, - float voltsPerDegreePerSecond, - float offset, int center); + double voltsPerDegreePerSecond, + double offset, int center); public static native void setAnalogGyroVoltsPerDegreePerSecond(int handle, - float voltsPerDegreePerSecond); + double voltsPerDegreePerSecond); public static native void resetAnalogGyro(int handle); public static native void calibrateAnalogGyro(int handle); - public static native void setAnalogGyroDeadband(int handle, float volts); + public static native void setAnalogGyroDeadband(int handle, double volts); - public static native float getAnalogGyroAngle(int handle); + public static native double getAnalogGyroAngle(int handle); public static native double getAnalogGyroRate(int handle); - public static native float getAnalogGyroOffset(int handle); + public static native double getAnalogGyroOffset(int handle); public static native int getAnalogGyroCenter(int handle); } diff --git a/wpilibj/src/athena/java/edu/wpi/first/wpilibj/hal/CompressorJNI.java b/wpilibj/src/athena/java/edu/wpi/first/wpilibj/hal/CompressorJNI.java index 6bd65f4b17..baf14270f6 100644 --- a/wpilibj/src/athena/java/edu/wpi/first/wpilibj/hal/CompressorJNI.java +++ b/wpilibj/src/athena/java/edu/wpi/first/wpilibj/hal/CompressorJNI.java @@ -20,7 +20,7 @@ public class CompressorJNI extends JNIWrapper { public static native boolean getCompressorPressureSwitch(int compressorHandle); - public static native float getCompressorCurrent(int compressorHandle); + public static native double getCompressorCurrent(int compressorHandle); public static native boolean getCompressorCurrentTooHighFault(int compressorHandle); diff --git a/wpilibj/src/athena/java/edu/wpi/first/wpilibj/hal/HAL.java b/wpilibj/src/athena/java/edu/wpi/first/wpilibj/hal/HAL.java index 416eeb69b4..ae8bd2cacc 100644 --- a/wpilibj/src/athena/java/edu/wpi/first/wpilibj/hal/HAL.java +++ b/wpilibj/src/athena/java/edu/wpi/first/wpilibj/hal/HAL.java @@ -105,7 +105,7 @@ public class HAL extends JNIWrapper { public static native int getJoystickAxisType(byte joystickNum, byte axis); - public static native float getMatchTime(); + public static native double getMatchTime(); public static native boolean getSystemActive(); diff --git a/wpilibj/src/athena/java/edu/wpi/first/wpilibj/hal/PWMJNI.java b/wpilibj/src/athena/java/edu/wpi/first/wpilibj/hal/PWMJNI.java index a84811de3a..9041ed75f1 100644 --- a/wpilibj/src/athena/java/edu/wpi/first/wpilibj/hal/PWMJNI.java +++ b/wpilibj/src/athena/java/edu/wpi/first/wpilibj/hal/PWMJNI.java @@ -33,15 +33,15 @@ public class PWMJNI extends DIOJNI { public static native void setPWMRaw(int pwmPortHandle, short value); - public static native void setPWMSpeed(int pwmPortHandle, float speed); + public static native void setPWMSpeed(int pwmPortHandle, double speed); - public static native void setPWMPosition(int pwmPortHandle, float position); + public static native void setPWMPosition(int pwmPortHandle, double position); public static native short getPWMRaw(int pwmPortHandle); - public static native float getPWMSpeed(int pwmPortHandle); + public static native double getPWMSpeed(int pwmPortHandle); - public static native float getPWMPosition(int pwmPortHandle); + public static native double getPWMPosition(int pwmPortHandle); public static native void setPWMDisabled(int pwmPortHandle); diff --git a/wpilibj/src/athena/java/edu/wpi/first/wpilibj/hal/PowerJNI.java b/wpilibj/src/athena/java/edu/wpi/first/wpilibj/hal/PowerJNI.java index ada08024b1..c97122d3f6 100644 --- a/wpilibj/src/athena/java/edu/wpi/first/wpilibj/hal/PowerJNI.java +++ b/wpilibj/src/athena/java/edu/wpi/first/wpilibj/hal/PowerJNI.java @@ -8,29 +8,29 @@ package edu.wpi.first.wpilibj.hal; public class PowerJNI extends JNIWrapper { - public static native float getVinVoltage(); + public static native double getVinVoltage(); - public static native float getVinCurrent(); + public static native double getVinCurrent(); - public static native float getUserVoltage6V(); + public static native double getUserVoltage6V(); - public static native float getUserCurrent6V(); + public static native double getUserCurrent6V(); public static native boolean getUserActive6V(); public static native int getUserCurrentFaults6V(); - public static native float getUserVoltage5V(); + public static native double getUserVoltage5V(); - public static native float getUserCurrent5V(); + public static native double getUserCurrent5V(); public static native boolean getUserActive5V(); public static native int getUserCurrentFaults5V(); - public static native float getUserVoltage3V3(); + public static native double getUserVoltage3V3(); - public static native float getUserCurrent3V3(); + public static native double getUserCurrent3V3(); public static native boolean getUserActive3V3(); diff --git a/wpilibj/src/athena/java/edu/wpi/first/wpilibj/hal/SerialPortJNI.java b/wpilibj/src/athena/java/edu/wpi/first/wpilibj/hal/SerialPortJNI.java index ab906a3e0d..9f683dedfc 100644 --- a/wpilibj/src/athena/java/edu/wpi/first/wpilibj/hal/SerialPortJNI.java +++ b/wpilibj/src/athena/java/edu/wpi/first/wpilibj/hal/SerialPortJNI.java @@ -24,7 +24,7 @@ public class SerialPortJNI extends JNIWrapper { public static native void serialSetFlowControl(byte port, byte flow); - public static native void serialSetTimeout(byte port, float timeout); + public static native void serialSetTimeout(byte port, double timeout); public static native void serialEnableTermination(byte port, char terminator); diff --git a/wpilibj/src/sim/java/edu/wpi/first/wpilibj/RobotDrive.java b/wpilibj/src/sim/java/edu/wpi/first/wpilibj/RobotDrive.java index 68e83a0ba9..6c49903d75 100644 --- a/wpilibj/src/sim/java/edu/wpi/first/wpilibj/RobotDrive.java +++ b/wpilibj/src/sim/java/edu/wpi/first/wpilibj/RobotDrive.java @@ -572,7 +572,7 @@ public class RobotDrive implements MotorSafety { * @param rotation The rate of rotation for the robot that is completely independent of the * magnitute or direction. [-1.0..1.0] */ - void holonomicDrive(float magnitude, float direction, float rotation) { + void holonomicDrive(double magnitude, double direction, double rotation) { mecanumDrive_Polar(magnitude, direction, rotation); } diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/AnalogCrossConnectTest.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/AnalogCrossConnectTest.java index a6f76032d2..b8fb2b2662 100644 --- a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/AnalogCrossConnectTest.java +++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/AnalogCrossConnectTest.java @@ -58,7 +58,7 @@ public class AnalogCrossConnectTest extends AbstractInterruptTest { @Test public void testAnalogOuput() { for (int i = 0; i < 50; i++) { - analogIO.getOutput().setVoltage(i / 10.0f); + analogIO.getOutput().setVoltage(i / 10.0); Timer.delay(kDelayTime); assertEquals(analogIO.getOutput().getVoltage(), analogIO.getInput().getVoltage(), 0.01); } @@ -68,10 +68,10 @@ public class AnalogCrossConnectTest extends AbstractInterruptTest { public void testAnalogTriggerBelowWindow() { // Given AnalogTrigger trigger = new AnalogTrigger(analogIO.getInput()); - trigger.setLimitsVoltage(2.0f, 3.0f); + trigger.setLimitsVoltage(2.0, 3.0); // When the output voltage is than less the lower limit - analogIO.getOutput().setVoltage(1.0f); + analogIO.getOutput().setVoltage(1.0); Timer.delay(kDelayTime); // Then the analog trigger is not in the window and the trigger state is off @@ -85,7 +85,7 @@ public class AnalogCrossConnectTest extends AbstractInterruptTest { public void testAnalogTriggerInWindow() { // Given AnalogTrigger trigger = new AnalogTrigger(analogIO.getInput()); - trigger.setLimitsVoltage(2.0f, 3.0f); + trigger.setLimitsVoltage(2.0, 3.0); // When the output voltage is within the lower and upper limits analogIO.getOutput().setVoltage(2.5f); @@ -102,10 +102,10 @@ public class AnalogCrossConnectTest extends AbstractInterruptTest { public void testAnalogTriggerAboveWindow() { // Given AnalogTrigger trigger = new AnalogTrigger(analogIO.getInput()); - trigger.setLimitsVoltage(2.0f, 3.0f); + trigger.setLimitsVoltage(2.0, 3.0); // When the output voltage is greater than the upper limit - analogIO.getOutput().setVoltage(4.0f); + analogIO.getOutput().setVoltage(4.0); Timer.delay(kDelayTime); // Then the analog trigger is not in the window and the trigger state is on @@ -119,7 +119,7 @@ public class AnalogCrossConnectTest extends AbstractInterruptTest { public void testAnalogTriggerCounter() { // Given AnalogTrigger trigger = new AnalogTrigger(analogIO.getInput()); - trigger.setLimitsVoltage(2.0f, 3.0f); + trigger.setLimitsVoltage(2.0, 3.0); Counter counter = new Counter(trigger); // When the analog output is turned low and high 50 times @@ -151,7 +151,7 @@ public class AnalogCrossConnectTest extends AbstractInterruptTest { @Override InterruptableSensorBase giveInterruptableSensorBase() { m_interruptTrigger = new AnalogTrigger(analogIO.getInput()); - m_interruptTrigger.setLimitsVoltage(2.0f, 3.0f); + m_interruptTrigger.setLimitsVoltage(2.0, 3.0); m_interruptTriggerOutput = new AnalogTriggerOutput(m_interruptTrigger, AnalogTriggerType.kState); return m_interruptTriggerOutput;