From 0cd05d1a42aa7c08a212dfb40b00a28dea99efbe Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Tue, 6 Sep 2016 00:01:45 -0700 Subject: [PATCH] Cleaned up integer type usage in wpilibc (#92) Replaced all unsigned types to signed and int32_t with int in wpilibc --- wpilibc/athena/include/ADXL345_I2C.h | 8 +- wpilibc/athena/include/ADXL345_SPI.h | 6 +- wpilibc/athena/include/ADXRS450_Gyro.h | 2 +- wpilibc/athena/include/AnalogAccelerometer.h | 2 +- wpilibc/athena/include/AnalogGyro.h | 13 ++- wpilibc/athena/include/AnalogInput.h | 32 +++--- wpilibc/athena/include/AnalogOutput.h | 4 +- wpilibc/athena/include/AnalogTrigger.h | 8 +- wpilibc/athena/include/AnalogTriggerOutput.h | 2 +- wpilibc/athena/include/CANJaguar.h | 58 ++++++----- wpilibc/athena/include/CANSpeedController.h | 2 +- wpilibc/athena/include/CANTalon.h | 42 ++++---- wpilibc/athena/include/CameraServer.h | 31 +++--- wpilibc/athena/include/Compressor.h | 4 +- wpilibc/athena/include/Counter.h | 12 +-- wpilibc/athena/include/CounterBase.h | 2 +- wpilibc/athena/include/DigitalGlitchFilter.h | 4 +- wpilibc/athena/include/DigitalInput.h | 6 +- wpilibc/athena/include/DigitalOutput.h | 8 +- wpilibc/athena/include/DigitalSource.h | 2 +- wpilibc/athena/include/DoubleSolenoid.h | 13 ++- wpilibc/athena/include/DriverStation.h | 28 +++--- wpilibc/athena/include/Encoder.h | 12 +-- wpilibc/athena/include/GearTooth.h | 2 +- wpilibc/athena/include/I2C.h | 21 ++-- wpilibc/athena/include/Jaguar.h | 2 +- wpilibc/athena/include/Joystick.h | 42 ++++---- wpilibc/athena/include/PWM.h | 10 +- wpilibc/athena/include/PWMSpeedController.h | 2 +- .../athena/include/PowerDistributionPanel.h | 6 +- wpilibc/athena/include/Preferences.h | 2 +- wpilibc/athena/include/Relay.h | 6 +- wpilibc/athena/include/RobotDrive.h | 28 +++--- wpilibc/athena/include/SD540.h | 2 +- wpilibc/athena/include/SPI.h | 22 ++--- wpilibc/athena/include/SafePWM.h | 2 +- wpilibc/athena/include/SerialPort.h | 18 ++-- wpilibc/athena/include/Servo.h | 2 +- wpilibc/athena/include/Solenoid.h | 6 +- wpilibc/athena/include/SolenoidBase.h | 10 +- wpilibc/athena/include/Spark.h | 2 +- wpilibc/athena/include/Talon.h | 2 +- wpilibc/athena/include/TalonSRX.h | 2 +- wpilibc/athena/include/USBCamera.h | 24 ++--- wpilibc/athena/include/Ultrasonic.h | 5 +- wpilibc/athena/include/Victor.h | 2 +- wpilibc/athena/include/VictorSP.h | 2 +- wpilibc/athena/include/Vision/AxisCamera.h | 3 +- wpilibc/athena/include/Vision/BaeUtilities.h | 2 + wpilibc/athena/include/Vision/FrcError.h | 2 + wpilibc/athena/include/Vision/Threshold.h | 2 + wpilibc/athena/include/Vision/VisionAPI.h | 17 ++-- wpilibc/athena/include/WPILib.h | 1 - wpilibc/athena/src/ADXL345_I2C.cpp | 10 +- wpilibc/athena/src/ADXL345_SPI.cpp | 8 +- wpilibc/athena/src/ADXL362.cpp | 28 +++--- wpilibc/athena/src/ADXRS450_Gyro.cpp | 37 ++++--- wpilibc/athena/src/AnalogAccelerometer.cpp | 2 +- wpilibc/athena/src/AnalogGyro.cpp | 14 +-- wpilibc/athena/src/AnalogInput.cpp | 44 ++++----- wpilibc/athena/src/AnalogOutput.cpp | 6 +- wpilibc/athena/src/AnalogTrigger.cpp | 10 +- wpilibc/athena/src/AnalogTriggerOutput.cpp | 2 +- wpilibc/athena/src/CANJaguar.cpp | 97 ++++++++++--------- wpilibc/athena/src/CANTalon.cpp | 60 ++++++------ wpilibc/athena/src/CameraServer.cpp | 26 ++--- wpilibc/athena/src/Compressor.cpp | 2 +- wpilibc/athena/src/Counter.cpp | 12 +-- wpilibc/athena/src/DigitalGlitchFilter.cpp | 10 +- wpilibc/athena/src/DigitalInput.cpp | 8 +- wpilibc/athena/src/DigitalOutput.cpp | 10 +- wpilibc/athena/src/DoubleSolenoid.cpp | 14 +-- wpilibc/athena/src/DriverStation.cpp | 26 ++--- wpilibc/athena/src/Encoder.cpp | 20 ++-- wpilibc/athena/src/GearTooth.cpp | 3 +- wpilibc/athena/src/I2C.cpp | 29 +++--- .../athena/src/InterruptableSensorBase.cpp | 2 +- wpilibc/athena/src/Jaguar.cpp | 2 +- wpilibc/athena/src/Joystick.cpp | 38 ++++---- wpilibc/athena/src/PIDController.cpp | 6 +- wpilibc/athena/src/PWM.cpp | 12 +-- wpilibc/athena/src/PWMSpeedController.cpp | 2 +- wpilibc/athena/src/PowerDistributionPanel.cpp | 5 +- wpilibc/athena/src/Preferences.cpp | 2 +- wpilibc/athena/src/Relay.cpp | 4 +- wpilibc/athena/src/RobotDrive.cpp | 26 ++--- wpilibc/athena/src/SD540.cpp | 2 +- wpilibc/athena/src/SPI.cpp | 32 +++--- wpilibc/athena/src/SafePWM.cpp | 2 +- wpilibc/athena/src/SerialPort.cpp | 18 ++-- wpilibc/athena/src/Servo.cpp | 2 +- wpilibc/athena/src/Solenoid.cpp | 4 +- wpilibc/athena/src/SolenoidBase.cpp | 19 ++-- wpilibc/athena/src/Spark.cpp | 2 +- wpilibc/athena/src/Talon.cpp | 2 +- wpilibc/athena/src/TalonSRX.cpp | 2 +- wpilibc/athena/src/Task.cpp | 6 +- wpilibc/athena/src/USBCamera.cpp | 34 ++++--- wpilibc/athena/src/Ultrasonic.cpp | 5 +- wpilibc/athena/src/Utility.cpp | 18 ++-- wpilibc/athena/src/Victor.cpp | 2 +- wpilibc/athena/src/VictorSP.cpp | 2 +- wpilibc/athena/src/Vision/AxisCamera.cpp | 10 +- wpilibc/athena/src/Vision/VisionAPI.cpp | 15 ++- wpilibc/shared/include/Error.h | 8 +- wpilibc/shared/include/ErrorBase.h | 14 +-- .../include/Filters/LinearDigitalFilter.h | 2 +- wpilibc/shared/include/GenericHID.h | 6 +- wpilibc/shared/include/PIDController.h | 2 +- wpilibc/shared/include/Task.h | 6 +- wpilibc/shared/include/Utility.h | 12 +-- wpilibc/shared/include/WPIErrors.h | 4 +- wpilibc/shared/src/Commands/Scheduler.cpp | 2 +- wpilibc/shared/src/Error.cpp | 4 +- wpilibc/shared/src/ErrorBase.cpp | 17 ++-- .../src/Filters/LinearDigitalFilter.cpp | 10 +- wpilibc/sim/include/AnalogGyro.h | 6 +- wpilibc/sim/include/AnalogInput.h | 12 +-- wpilibc/sim/include/Counter.h | 12 +-- wpilibc/sim/include/CounterBase.h | 2 +- wpilibc/sim/include/DigitalInput.h | 8 +- wpilibc/sim/include/DoubleSolenoid.h | 5 +- wpilibc/sim/include/DriverStation.h | 30 +++--- wpilibc/sim/include/Encoder.h | 12 +-- wpilibc/sim/include/Jaguar.h | 2 +- wpilibc/sim/include/Joystick.h | 36 +++---- wpilibc/sim/include/Notifier.h | 2 +- wpilibc/sim/include/PWM.h | 16 +-- wpilibc/sim/include/Relay.h | 6 +- wpilibc/sim/include/RobotDrive.h | 30 +++--- wpilibc/sim/include/SafePWM.h | 2 +- wpilibc/sim/include/Solenoid.h | 4 +- wpilibc/sim/include/Talon.h | 2 +- wpilibc/sim/include/Victor.h | 2 +- wpilibc/sim/include/simulation/MainNode.h | 2 +- wpilibc/sim/src/AnalogGyro.cpp | 6 +- wpilibc/sim/src/AnalogInput.cpp | 4 +- wpilibc/sim/src/DigitalInput.cpp | 6 +- wpilibc/sim/src/DoubleSolenoid.cpp | 6 +- wpilibc/sim/src/DriverStation.cpp | 26 ++--- wpilibc/sim/src/Encoder.cpp | 15 ++- wpilibc/sim/src/Jaguar.cpp | 2 +- wpilibc/sim/src/Joystick.cpp | 38 ++++---- wpilibc/sim/src/Notifier.cpp | 2 +- wpilibc/sim/src/PIDController.cpp | 4 +- wpilibc/sim/src/PWM.cpp | 10 +- wpilibc/sim/src/Relay.cpp | 4 +- wpilibc/sim/src/RobotDrive.cpp | 26 ++--- wpilibc/sim/src/SafePWM.cpp | 2 +- wpilibc/sim/src/SampleRobot.cpp | 2 +- wpilibc/sim/src/Solenoid.cpp | 4 +- wpilibc/sim/src/Talon.cpp | 2 +- wpilibc/sim/src/Utility.cpp | 19 ++-- wpilibc/sim/src/Victor.cpp | 2 +- wpilibcIntegrationTests/include/TestBench.h | 2 +- .../include/command/MockCommand.h | 20 ++-- .../src/AnalogLoopTest.cpp | 12 +-- wpilibcIntegrationTests/src/CANJaguarTest.cpp | 12 +-- wpilibcIntegrationTests/src/CANTalonTest.cpp | 2 +- wpilibcIntegrationTests/src/DIOLoopTest.cpp | 10 +- .../src/FakeEncoderTest.cpp | 2 +- wpilibcIntegrationTests/src/MutexTest.cpp | 4 +- .../src/TiltPanCameraTest.cpp | 4 +- .../src/command/CommandTest.cpp | 5 +- wpilibj/src/athena/cpp/lib/CANJNI.cpp | 4 +- wpilibj/src/athena/cpp/lib/HALUtil.cpp | 2 +- wpilibj/src/athena/cpp/lib/HALUtil.h | 4 +- wpilibj/src/athena/cpp/lib/InterruptJNI.cpp | 6 +- wpilibj/src/athena/cpp/lib/PowerJNI.cpp | 6 +- 169 files changed, 914 insertions(+), 943 deletions(-) diff --git a/wpilibc/athena/include/ADXL345_I2C.h b/wpilibc/athena/include/ADXL345_I2C.h index e161fc4bb7..d9ffee5541 100644 --- a/wpilibc/athena/include/ADXL345_I2C.h +++ b/wpilibc/athena/include/ADXL345_I2C.h @@ -24,10 +24,10 @@ */ class ADXL345_I2C : public Accelerometer, public LiveWindowSendable { protected: - static const uint8_t kAddress = 0x1D; - static const uint8_t kPowerCtlRegister = 0x2D; - static const uint8_t kDataFormatRegister = 0x31; - static const uint8_t kDataRegister = 0x32; + static const int kAddress = 0x1D; + static const int kPowerCtlRegister = 0x2D; + static const int kDataFormatRegister = 0x31; + static const int kDataRegister = 0x32; static constexpr double kGsPerLSB = 0.00390625; enum PowerCtlFields { kPowerCtl_Link = 0x20, diff --git a/wpilibc/athena/include/ADXL345_SPI.h b/wpilibc/athena/include/ADXL345_SPI.h index 14be56333d..2345b896dd 100644 --- a/wpilibc/athena/include/ADXL345_SPI.h +++ b/wpilibc/athena/include/ADXL345_SPI.h @@ -27,9 +27,9 @@ class DigitalOutput; */ class ADXL345_SPI : public Accelerometer, public LiveWindowSendable { protected: - static const uint8_t kPowerCtlRegister = 0x2D; - static const uint8_t kDataFormatRegister = 0x31; - static const uint8_t kDataRegister = 0x32; + static const int kPowerCtlRegister = 0x2D; + static const int kDataFormatRegister = 0x31; + static const int kDataRegister = 0x32; static constexpr double kGsPerLSB = 0.00390625; enum SPIAddressFields { kAddress_Read = 0x80, kAddress_MultiByte = 0x40 }; enum PowerCtlFields { diff --git a/wpilibc/athena/include/ADXRS450_Gyro.h b/wpilibc/athena/include/ADXRS450_Gyro.h index 94222dc278..73d38d0549 100644 --- a/wpilibc/athena/include/ADXRS450_Gyro.h +++ b/wpilibc/athena/include/ADXRS450_Gyro.h @@ -39,5 +39,5 @@ class ADXRS450_Gyro : public GyroBase { private: SPI m_spi; - uint16_t ReadRegister(uint8_t reg); + uint16_t ReadRegister(int reg); }; diff --git a/wpilibc/athena/include/AnalogAccelerometer.h b/wpilibc/athena/include/AnalogAccelerometer.h index f5ace7c3c6..670bdd9534 100644 --- a/wpilibc/athena/include/AnalogAccelerometer.h +++ b/wpilibc/athena/include/AnalogAccelerometer.h @@ -25,7 +25,7 @@ class AnalogAccelerometer : public SensorBase, public PIDSource, public LiveWindowSendable { public: - explicit AnalogAccelerometer(int32_t channel); + explicit AnalogAccelerometer(int channel); explicit AnalogAccelerometer(AnalogInput* channel); explicit AnalogAccelerometer(std::shared_ptr channel); virtual ~AnalogAccelerometer() = default; diff --git a/wpilibc/athena/include/AnalogGyro.h b/wpilibc/athena/include/AnalogGyro.h index 739181d1fb..ea7ecc39a1 100644 --- a/wpilibc/athena/include/AnalogGyro.h +++ b/wpilibc/athena/include/AnalogGyro.h @@ -29,23 +29,22 @@ class AnalogInput; */ class AnalogGyro : public GyroBase { public: - static const uint32_t kOversampleBits = 10; - static const uint32_t kAverageBits = 0; + 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; - explicit AnalogGyro(int32_t channel); + explicit AnalogGyro(int channel); explicit AnalogGyro(AnalogInput* channel); explicit AnalogGyro(std::shared_ptr channel); - AnalogGyro(int32_t channel, uint32_t center, float offset); - AnalogGyro(std::shared_ptr channel, uint32_t center, - float offset); + AnalogGyro(int channel, int center, float offset); + AnalogGyro(std::shared_ptr channel, int center, float offset); virtual ~AnalogGyro(); float GetAngle() const override; double GetRate() const override; - virtual uint32_t GetCenter() const; + virtual int GetCenter() const; virtual float GetOffset() const; void SetSensitivity(float voltsPerDegreePerSecond); void SetDeadband(float volts); diff --git a/wpilibc/athena/include/AnalogInput.h b/wpilibc/athena/include/AnalogInput.h index 9e84ed7003..88f81da22a 100644 --- a/wpilibc/athena/include/AnalogInput.h +++ b/wpilibc/athena/include/AnalogInput.h @@ -34,35 +34,35 @@ class AnalogInput : public SensorBase, friend class AnalogGyro; public: - static const uint8_t kAccumulatorModuleNumber = 1; - static const uint32_t kAccumulatorNumChannels = 2; - static const uint32_t kAccumulatorChannels[kAccumulatorNumChannels]; + static const int kAccumulatorModuleNumber = 1; + static const int kAccumulatorNumChannels = 2; + static const int kAccumulatorChannels[kAccumulatorNumChannels]; - explicit AnalogInput(uint32_t channel); + explicit AnalogInput(int channel); virtual ~AnalogInput(); - int32_t GetValue() const; - int32_t GetAverageValue() const; + int GetValue() const; + int GetAverageValue() const; float GetVoltage() const; float GetAverageVoltage() const; - uint32_t GetChannel() const; + int GetChannel() const; - void SetAverageBits(int32_t bits); - int32_t GetAverageBits() const; - void SetOversampleBits(int32_t bits); - int32_t GetOversampleBits() const; + void SetAverageBits(int bits); + int GetAverageBits() const; + void SetOversampleBits(int bits); + int GetOversampleBits() const; - int32_t GetLSBWeight() const; - int32_t GetOffset() const; + int GetLSBWeight() const; + int GetOffset() const; bool IsAccumulatorChannel() const; void InitAccumulator(); void SetAccumulatorInitialValue(int64_t value); void ResetAccumulator(); - void SetAccumulatorCenter(int32_t center); - void SetAccumulatorDeadband(int32_t deadband); + void SetAccumulatorCenter(int center); + void SetAccumulatorDeadband(int deadband); int64_t GetAccumulatorValue() const; int64_t GetAccumulatorCount() const; void GetAccumulatorOutput(int64_t& value, int64_t& count) const; @@ -80,7 +80,7 @@ class AnalogInput : public SensorBase, std::shared_ptr GetTable() const override; private: - uint32_t m_channel; + int m_channel; // TODO: Adjust HAL to avoid use of raw pointers. HAL_AnalogInputHandle m_port; int64_t m_accumulatorOffset; diff --git a/wpilibc/athena/include/AnalogOutput.h b/wpilibc/athena/include/AnalogOutput.h index 3cde877939..3fe5687c3c 100644 --- a/wpilibc/athena/include/AnalogOutput.h +++ b/wpilibc/athena/include/AnalogOutput.h @@ -21,7 +21,7 @@ */ class AnalogOutput : public SensorBase, public LiveWindowSendable { public: - explicit AnalogOutput(uint32_t channel); + explicit AnalogOutput(int channel); virtual ~AnalogOutput(); void SetVoltage(float voltage); @@ -35,7 +35,7 @@ class AnalogOutput : public SensorBase, public LiveWindowSendable { std::shared_ptr GetTable() const override; protected: - uint32_t m_channel; + int m_channel; HAL_AnalogOutputHandle m_port; std::shared_ptr m_table; diff --git a/wpilibc/athena/include/AnalogTrigger.h b/wpilibc/athena/include/AnalogTrigger.h index bbad565dc5..6634009ad6 100644 --- a/wpilibc/athena/include/AnalogTrigger.h +++ b/wpilibc/athena/include/AnalogTrigger.h @@ -19,22 +19,22 @@ class AnalogTrigger : public SensorBase { friend class AnalogTriggerOutput; public: - explicit AnalogTrigger(int32_t channel); + explicit AnalogTrigger(int channel); explicit AnalogTrigger(AnalogInput* channel); virtual ~AnalogTrigger(); void SetLimitsVoltage(float lower, float upper); - void SetLimitsRaw(int32_t lower, int32_t upper); + void SetLimitsRaw(int lower, int upper); void SetAveraged(bool useAveragedValue); void SetFiltered(bool useFilteredValue); - int32_t GetIndex() const; + int GetIndex() const; bool GetInWindow(); bool GetTriggerState(); std::shared_ptr CreateOutput( AnalogTriggerType type) const; private: - uint8_t m_index; + int m_index; HAL_AnalogTriggerHandle m_trigger; AnalogInput* m_analogInput = nullptr; bool m_ownsAnalog = false; diff --git a/wpilibc/athena/include/AnalogTriggerOutput.h b/wpilibc/athena/include/AnalogTriggerOutput.h index 34ef5bf737..1da4724fdc 100644 --- a/wpilibc/athena/include/AnalogTriggerOutput.h +++ b/wpilibc/athena/include/AnalogTriggerOutput.h @@ -54,7 +54,7 @@ class AnalogTriggerOutput : public DigitalSource { HAL_Handle GetPortHandleForRouting() const override; AnalogTriggerType GetAnalogTriggerTypeForRouting() const override; bool IsAnalogTrigger() const override; - uint32_t GetChannel() const override; + int GetChannel() const override; protected: AnalogTriggerOutput(const AnalogTrigger& trigger, diff --git a/wpilibc/athena/include/CANJaguar.h b/wpilibc/athena/include/CANJaguar.h index d1759e1e3c..3b1aeb4fc4 100644 --- a/wpilibc/athena/include/CANJaguar.h +++ b/wpilibc/athena/include/CANJaguar.h @@ -22,7 +22,6 @@ #include "MotorSafety.h" #include "MotorSafetyHelper.h" #include "PIDOutput.h" -#include "Resource.h" #include "tables/ITableListener.h" /** @@ -35,7 +34,7 @@ class CANJaguar : public MotorSafety, public ITableListener { public: // The internal PID control loop in the Jaguar runs at 1kHz. - static const int32_t kControllerRate = 1000; + static const int kControllerRate = 1000; static constexpr double kApproxBusVoltage = 12.0; // Control mode tags @@ -52,11 +51,11 @@ class CANJaguar : public MotorSafety, static const struct PotentiometerStruct { } Potentiometer; - explicit CANJaguar(uint8_t deviceNumber); + explicit CANJaguar(int deviceNumber); virtual ~CANJaguar(); - uint8_t getDeviceNumber() const; - uint8_t GetHardwareVersion() const; + int getDeviceNumber() const; + int GetHardwareVersion() const; // PIDOutput interface void PIDWrite(float output) override; @@ -91,7 +90,7 @@ class CANJaguar : public MotorSafety, void SetVoltageMode(QuadEncoderStruct, uint16_t codesPerRev); void SetVoltageMode(PotentiometerStruct); - void Set(float value, uint8_t syncGroup); + void Set(float value, int syncGroup); // CANSpeedController interface float Get() const override; @@ -115,7 +114,7 @@ class CANJaguar : public MotorSafety, bool GetReverseLimitOK() const override; uint16_t GetFaults() const override; void SetVoltageRampRate(double rampRate) override; - uint32_t GetFirmwareVersion() const override; + int GetFirmwareVersion() const override; void ConfigNeutralMode(NeutralMode mode) override; void ConfigEncoderCodesPerRev(uint16_t codesPerRev) override; void ConfigPotentiometerTurns(uint16_t turns) override; @@ -139,7 +138,7 @@ class CANJaguar : public MotorSafety, bool IsSafetyEnabled() const override; void SetSafetyEnabled(bool enabled) override; void GetDescription(std::ostringstream& desc) const override; - uint8_t GetDeviceID() const; + int GetDeviceID() const; // SpeedController overrides void SetInverted(bool isInverted) override; @@ -147,28 +146,27 @@ class CANJaguar : public MotorSafety, protected: // Control mode helpers - void SetSpeedReference(uint8_t reference); - uint8_t GetSpeedReference() const; + void SetSpeedReference(int reference); + int GetSpeedReference() const; - void SetPositionReference(uint8_t reference); - uint8_t GetPositionReference() const; + void SetPositionReference(int reference); + int GetPositionReference() const; - uint8_t packPercentage(uint8_t* buffer, double value); - uint8_t packFXP8_8(uint8_t* buffer, double value); - uint8_t packFXP16_16(uint8_t* buffer, double value); - uint8_t packint16_t(uint8_t* buffer, int16_t value); - uint8_t packint32_t(uint8_t* buffer, int32_t value); + int packPercentage(uint8_t* buffer, double value); + int packFXP8_8(uint8_t* buffer, double value); + int packFXP16_16(uint8_t* buffer, double value); + int packInt16(uint8_t* buffer, int16_t value); + int packInt32(uint8_t* buffer, int32_t value); double unpackPercentage(uint8_t* buffer) const; double unpackFXP8_8(uint8_t* buffer) const; double unpackFXP16_16(uint8_t* buffer) const; - int16_t unpackint16_t(uint8_t* buffer) const; - int32_t unpackint32_t(uint8_t* buffer) const; + int16_t unpackInt16(uint8_t* buffer) const; + int32_t unpackInt32(uint8_t* buffer) const; - void sendMessage(uint32_t messageID, const uint8_t* data, uint8_t dataSize, - int32_t period = CAN_SEND_PERIOD_NO_REPEAT); - void requestMessage(uint32_t messageID, - int32_t period = CAN_SEND_PERIOD_NO_REPEAT); - bool getMessage(uint32_t messageID, uint32_t mask, uint8_t* data, + void sendMessage(int messageID, const uint8_t* data, uint8_t dataSize, + int period = CAN_SEND_PERIOD_NO_REPEAT); + void requestMessage(int messageID, int period = CAN_SEND_PERIOD_NO_REPEAT); + bool getMessage(int messageID, uint32_t mask, uint8_t* data, uint8_t* dataSize) const; void setupPeriodicStatus(); @@ -176,13 +174,13 @@ class CANJaguar : public MotorSafety, mutable priority_recursive_mutex m_mutex; - uint8_t m_deviceNumber; + int m_deviceNumber; float m_value = 0.0f; // Parameters/configuration ControlMode m_controlMode = kPercentVbus; - uint8_t m_speedReference = LM_REF_NONE; - uint8_t m_positionReference = LM_REF_NONE; + int m_speedReference = LM_REF_NONE; + int m_positionReference = LM_REF_NONE; double m_p = 0.0; double m_i = 0.0; double m_d = 0.0; @@ -221,10 +219,10 @@ class CANJaguar : public MotorSafety, mutable float m_temperature = 0.0f; mutable double m_position = 0.0; mutable double m_speed = 0.0; - mutable uint8_t m_limits = 0x00; + mutable int m_limits = 0x00; mutable uint16_t m_faults = 0x0000; - uint32_t m_firmwareVersion = 0; - uint8_t m_hardwareVersion = 0; + int m_firmwareVersion = 0; + int m_hardwareVersion = 0; // Which periodic status messages have we received at least once? mutable std::atomic m_receivedStatusMessage0{false}; diff --git a/wpilibc/athena/include/CANSpeedController.h b/wpilibc/athena/include/CANSpeedController.h index ccd3710e23..43b0da75ff 100644 --- a/wpilibc/athena/include/CANSpeedController.h +++ b/wpilibc/athena/include/CANSpeedController.h @@ -84,7 +84,7 @@ class CANSpeedController : public SpeedController { virtual bool GetReverseLimitOK() const = 0; virtual uint16_t GetFaults() const = 0; virtual void SetVoltageRampRate(double rampRate) = 0; - virtual uint32_t GetFirmwareVersion() const = 0; + virtual int GetFirmwareVersion() const = 0; virtual void ConfigNeutralMode(NeutralMode mode) = 0; virtual void ConfigEncoderCodesPerRev(uint16_t codesPerRev) = 0; virtual void ConfigPotentiometerTurns(uint16_t turns) = 0; diff --git a/wpilibc/athena/include/CANTalon.h b/wpilibc/athena/include/CANTalon.h index 9292877e37..fb2e33d37c 100644 --- a/wpilibc/athena/include/CANTalon.h +++ b/wpilibc/athena/include/CANTalon.h @@ -119,7 +119,7 @@ class CANTalon : public MotorSafety, * Value should be between 1ms and 255ms. If value is zero * then Talon will default to 1ms. If value exceeds 255ms API will cap it. */ - unsigned int timeDurMs; + int timeDurMs; /** * Which slot to get PIDF gains. * PID is used for position servo. @@ -127,7 +127,7 @@ class CANTalon : public MotorSafety, * Typically this is hardcoded to the a particular slot, but you are free * gain schedule if need be. */ - unsigned int profileSlotSelect; + int profileSlotSelect; /** * Set to true to only perform the velocity feed-forward and not perform * position servo. This is useful when learning how the position servo @@ -181,15 +181,15 @@ class CANTalon : public MotorSafety, * them into the Talon's low-level buffer, allowing the Talon to act on * them. */ - unsigned int topBufferRem; + int topBufferRem; /** * The number of points in the top trajectory buffer. */ - unsigned int topBufferCnt; + int topBufferCnt; /** * The number of points in the low level Talon buffer. */ - unsigned int btmBufferCnt; + int btmBufferCnt; /** * Set if isUnderrun ever gets set. * Only is cleared by clearMotionProfileHasUnderrun() to ensure @@ -253,7 +253,7 @@ class CANTalon : public MotorSafety, void SetI(double i) override; void SetD(double d) override; void SetF(double f); - void SetIzone(unsigned iz); + void SetIzone(int iz); void SetPID(double p, double i, double d) override; virtual void SetPID(double p, double i, double d, double f); double GetP() const override; @@ -269,7 +269,7 @@ class CANTalon : public MotorSafety, double GetPosition() const override; double GetSpeed() const override; virtual int GetClosedLoopError() const; - virtual void SetAllowableClosedLoopErr(uint32_t allowableCloseLoopError); + virtual void SetAllowableClosedLoopErr(int allowableCloseLoopError); virtual int GetAnalogIn() const; virtual void SetAnalogPosition(int newPosition); virtual int GetAnalogInRaw() const; @@ -298,7 +298,7 @@ class CANTalon : public MotorSafety, void ClearStickyFaults(); void SetVoltageRampRate(double rampRate) override; virtual void SetVoltageCompensationRampRate(double rampRate); - uint32_t GetFirmwareVersion() const override; + int GetFirmwareVersion() const override; void ConfigNeutralMode(NeutralMode mode) override; void ConfigEncoderCodesPerRev(uint16_t codesPerRev) override; void ConfigPotentiometerTurns(uint16_t turns) override; @@ -347,8 +347,8 @@ class CANTalon : public MotorSafety, * edge, pass false to clear the position on falling edge. */ void EnableZeroSensorPositionOnIndex(bool enable, bool risingEdge); - void ConfigSetParameter(uint32_t paramEnum, double value); - bool GetParameter(uint32_t paramEnum, double& dvalue) const; + void ConfigSetParameter(int paramEnum, double value); + bool GetParameter(int paramEnum, double& dvalue) const; void ConfigFaultTime(float faultTime) override; virtual void SetControlMode(ControlMode mode); @@ -469,8 +469,8 @@ class CANTalon : public MotorSafety, int m_deviceNumber; std::unique_ptr m_impl; std::unique_ptr m_safetyHelper; - int m_profile = 0; // Profile from CANTalon to use. Set to zero until we can - // actually test this. + int m_profile = 0; // Profile from CANTalon to use. Set to zero until we + // can actually test this. bool m_controlEnabled = true; bool m_stopped = false; @@ -485,7 +485,7 @@ class CANTalon : public MotorSafety, * count (4X). Caller can use ConfigEncoderCodesPerRev to set the quadrature * encoder CPR. */ - uint32_t m_codesPerRev = 0; + int m_codesPerRev = 0; /** * Number of turns per rotation. For example, a 10-turn pot spins ten full * rotations from a wiper voltage of zero to 3.3 volts. Therefore knowing @@ -494,14 +494,14 @@ class CANTalon : public MotorSafety, * behaves as it did during the 2015 season, there are 1024 position units * from zero to 3.3V. */ - uint32_t m_numPotTurns = 0; + int m_numPotTurns = 0; /** * Although the Talon handles feedback selection, caching the feedback * selection is helpful at the API level for scaling into rotations and RPM. */ FeedbackDevice m_feedbackDevice = QuadEncoder; - static constexpr unsigned int kDelayForSolicitedSignalsUs = 4000; + static constexpr int kDelayForSolicitedSignalsUs = 4000; /** * @param devToLookup FeedbackDevice to lookup the scalar for. Because Talon * allows multiple sensors to be attached simultaneously, @@ -531,8 +531,8 @@ class CANTalon : public MotorSafety, * @return fullRotations in native engineering units of the Talon SRX * firmware. */ - int32_t ScaleRotationsToNativeUnits(FeedbackDevice devToLookup, - double fullRotations) const; + int ScaleRotationsToNativeUnits(FeedbackDevice devToLookup, + double fullRotations) const; /** * @param rpm double precision value representing number of rotations per * minute of selected feedback sensor. If user has never called @@ -544,8 +544,7 @@ class CANTalon : public MotorSafety, * @return sensor velocity in native engineering units of the Talon SRX * firmware. */ - int32_t ScaleVelocityToNativeUnits(FeedbackDevice devToLookup, - double rpm) const; + int ScaleVelocityToNativeUnits(FeedbackDevice devToLookup, double rpm) const; /** * @param nativePos integral position of the feedback sensor in native * Talon SRX units. If user has never called the config @@ -558,7 +557,7 @@ class CANTalon : public MotorSafety, * performed. */ double ScaleNativeUnitsToRotations(FeedbackDevice devToLookup, - int32_t nativePos) const; + int nativePos) const; /** * @param nativeVel integral velocity of the feedback sensor in native * Talon SRX units. If user has never called the config @@ -570,8 +569,7 @@ class CANTalon : public MotorSafety, * @return double precision of sensor velocity in RPM, unless config was never * performed. */ - double ScaleNativeUnitsToRpm(FeedbackDevice devToLookup, - int32_t nativeVel) const; + double ScaleNativeUnitsToRpm(FeedbackDevice devToLookup, int nativeVel) const; // LiveWindow stuff. std::shared_ptr m_table; diff --git a/wpilibc/athena/include/CameraServer.h b/wpilibc/athena/include/CameraServer.h index ba47937809..256e5cb097 100644 --- a/wpilibc/athena/include/CameraServer.h +++ b/wpilibc/athena/include/CameraServer.h @@ -23,11 +23,11 @@ class CameraServer : public ErrorBase { private: static constexpr uint16_t kPort = 1180; static constexpr uint8_t kMagicNumber[] = {0x01, 0x00, 0x00, 0x00}; - static constexpr uint32_t kSize640x480 = 0; - static constexpr uint32_t kSize320x240 = 1; - static constexpr uint32_t kSize160x120 = 2; - static constexpr int32_t kHardwareCompression = -1; - static constexpr uint32_t kMaxImageSize = 200000; + static constexpr int kSize640x480 = 0; + static constexpr int kSize320x240 = 1; + static constexpr int kSize160x120 = 2; + static constexpr int kHardwareCompression = -1; + static constexpr int kMaxImageSize = 200000; protected: CameraServer(); @@ -38,22 +38,21 @@ class CameraServer : public ErrorBase { priority_recursive_mutex m_imageMutex; std::condition_variable_any m_newImageVariable; std::vector m_dataPool; - unsigned int m_quality; + int m_quality; bool m_autoCaptureStarted; bool m_hwClient; - std::tuple m_imageData; + std::tuple m_imageData; void Serve(); void AutoCapture(); - void SetImageData(uint8_t* data, unsigned int size, unsigned int start = 0, + void SetImageData(uint8_t* data, int size, int start = 0, bool imaqData = false); - void FreeImageData( - std::tuple imageData); + void FreeImageData(std::tuple imageData); struct Request { - uint32_t fps; - int32_t compression; - uint32_t size; + int fps; + int compression; + int size; }; public: @@ -76,8 +75,8 @@ class CameraServer : public ErrorBase { bool IsAutoCaptureStarted(); - void SetQuality(unsigned int quality); - unsigned int GetQuality(); + void SetQuality(int quality); + int GetQuality(); - void SetSize(unsigned int size); + void SetSize(int size); }; diff --git a/wpilibc/athena/include/Compressor.h b/wpilibc/athena/include/Compressor.h index 618a95e6c5..99e74e2cc1 100644 --- a/wpilibc/athena/include/Compressor.h +++ b/wpilibc/athena/include/Compressor.h @@ -23,7 +23,7 @@ class Compressor : public SensorBase, public ITableListener { public: // Default PCM ID is 0 - explicit Compressor(uint8_t pcmID = GetDefaultSolenoidModule()); + explicit Compressor(int pcmID = GetDefaultSolenoidModule()); virtual ~Compressor() = default; void Start(); @@ -59,7 +59,7 @@ class Compressor : public SensorBase, private: void SetCompressor(bool on); - uint8_t m_module; + int m_module; std::shared_ptr m_table; }; diff --git a/wpilibc/athena/include/Counter.h b/wpilibc/athena/include/Counter.h index ab8fb34200..6504eceb9b 100644 --- a/wpilibc/athena/include/Counter.h +++ b/wpilibc/athena/include/Counter.h @@ -39,7 +39,7 @@ class Counter : public SensorBase, kExternalDirection = 3 }; explicit Counter(Mode mode = kTwoPulse); - explicit Counter(int32_t channel); + explicit Counter(int channel); explicit Counter(DigitalSource* source); explicit Counter(std::shared_ptr source); DEPRECATED("Use pass-by-reference instead.") @@ -51,7 +51,7 @@ class Counter : public SensorBase, std::shared_ptr downSource, bool inverted); virtual ~Counter(); - void SetUpSource(int32_t channel); + void SetUpSource(int channel); void SetUpSource(AnalogTrigger* analogTrigger, AnalogTriggerType triggerType); void SetUpSource(std::shared_ptr analogTrigger, AnalogTriggerType triggerType); @@ -61,7 +61,7 @@ class Counter : public SensorBase, void SetUpSourceEdge(bool risingEdge, bool fallingEdge); void ClearUpSource(); - void SetDownSource(int32_t channel); + void SetDownSource(int channel); void SetDownSource(AnalogTrigger* analogTrigger, AnalogTriggerType triggerType); void SetDownSource(std::shared_ptr analogTrigger, @@ -80,7 +80,7 @@ class Counter : public SensorBase, void SetReverseDirection(bool reverseDirection); // CounterBase interface - int32_t Get() const override; + int Get() const override; void Reset() override; double GetPeriod() const override; void SetMaxPeriod(double maxPeriod) override; @@ -90,7 +90,7 @@ class Counter : public SensorBase, void SetSamplesToAverage(int samplesToAverage); int GetSamplesToAverage() const; - int32_t GetFPGAIndex() const { return m_index; } + int GetFPGAIndex() const { return m_index; } void UpdateTable() override; void StartLiveWindowMode() override; @@ -108,7 +108,7 @@ class Counter : public SensorBase, HAL_CounterHandle m_counter = HAL_kInvalidHandle; private: - int32_t m_index = 0; ///< The index of this counter. + int m_index = 0; ///< The index of this counter. std::shared_ptr m_table; friend class DigitalGlitchFilter; diff --git a/wpilibc/athena/include/CounterBase.h b/wpilibc/athena/include/CounterBase.h index 633b79517c..21df0b799a 100644 --- a/wpilibc/athena/include/CounterBase.h +++ b/wpilibc/athena/include/CounterBase.h @@ -22,7 +22,7 @@ class CounterBase { enum EncodingType { k1X, k2X, k4X }; virtual ~CounterBase() = default; - virtual int32_t Get() const = 0; + virtual int Get() const = 0; virtual void Reset() = 0; virtual double GetPeriod() const = 0; virtual void SetMaxPeriod(double maxPeriod) = 0; diff --git a/wpilibc/athena/include/DigitalGlitchFilter.h b/wpilibc/athena/include/DigitalGlitchFilter.h index a84a42785e..bae2fba0be 100644 --- a/wpilibc/athena/include/DigitalGlitchFilter.h +++ b/wpilibc/athena/include/DigitalGlitchFilter.h @@ -34,10 +34,10 @@ class DigitalGlitchFilter : public SensorBase { void Remove(Encoder* input); void Remove(Counter* input); - void SetPeriodCycles(uint32_t fpga_cycles); + void SetPeriodCycles(int fpga_cycles); void SetPeriodNanoSeconds(uint64_t nanoseconds); - uint32_t GetPeriodCycles(); + int GetPeriodCycles(); uint64_t GetPeriodNanoSeconds(); private: diff --git a/wpilibc/athena/include/DigitalInput.h b/wpilibc/athena/include/DigitalInput.h index 9017b76650..1b18100571 100644 --- a/wpilibc/athena/include/DigitalInput.h +++ b/wpilibc/athena/include/DigitalInput.h @@ -27,10 +27,10 @@ class DigitalGlitchFilter; */ class DigitalInput : public DigitalSource, public LiveWindowSendable { public: - explicit DigitalInput(uint32_t channel); + explicit DigitalInput(int channel); virtual ~DigitalInput(); bool Get() const; - uint32_t GetChannel() const override; + int GetChannel() const override; // Digital Source Interface HAL_Handle GetPortHandleForRouting() const override; @@ -45,7 +45,7 @@ class DigitalInput : public DigitalSource, public LiveWindowSendable { std::shared_ptr GetTable() const; private: - uint32_t m_channel; + int m_channel; HAL_DigitalHandle m_handle; std::shared_ptr m_table; diff --git a/wpilibc/athena/include/DigitalOutput.h b/wpilibc/athena/include/DigitalOutput.h index cbe84fe954..50255707ab 100644 --- a/wpilibc/athena/include/DigitalOutput.h +++ b/wpilibc/athena/include/DigitalOutput.h @@ -25,11 +25,11 @@ class DigitalOutput : public DigitalSource, public ITableListener, public LiveWindowSendable { public: - explicit DigitalOutput(uint32_t channel); + explicit DigitalOutput(int channel); virtual ~DigitalOutput(); void Set(bool value); - bool Get(); - uint32_t GetChannel() const override; + bool Get() const; + int GetChannel() const override; void Pulse(float length); bool IsPulsing() const; void SetPWMRate(float rate); @@ -52,7 +52,7 @@ class DigitalOutput : public DigitalSource, std::shared_ptr GetTable() const; private: - uint32_t m_channel; + int m_channel; HAL_DigitalHandle m_handle; HAL_DigitalPWMHandle m_pwmGenerator; diff --git a/wpilibc/athena/include/DigitalSource.h b/wpilibc/athena/include/DigitalSource.h index 40354001a7..94512fce10 100644 --- a/wpilibc/athena/include/DigitalSource.h +++ b/wpilibc/athena/include/DigitalSource.h @@ -26,5 +26,5 @@ class DigitalSource : public InterruptableSensorBase { virtual HAL_Handle GetPortHandleForRouting() const = 0; virtual AnalogTriggerType GetAnalogTriggerTypeForRouting() const = 0; virtual bool IsAnalogTrigger() const = 0; - virtual uint32_t GetChannel() const = 0; + virtual int GetChannel() const = 0; }; diff --git a/wpilibc/athena/include/DoubleSolenoid.h b/wpilibc/athena/include/DoubleSolenoid.h index 41528ab7cb..d3033e6ea8 100644 --- a/wpilibc/athena/include/DoubleSolenoid.h +++ b/wpilibc/athena/include/DoubleSolenoid.h @@ -28,9 +28,8 @@ class DoubleSolenoid : public SolenoidBase, public: enum Value { kOff, kForward, kReverse }; - explicit DoubleSolenoid(uint32_t forwardChannel, uint32_t reverseChannel); - DoubleSolenoid(uint8_t moduleNumber, uint32_t forwardChannel, - uint32_t reverseChannel); + explicit DoubleSolenoid(int forwardChannel, int reverseChannel); + DoubleSolenoid(int moduleNumber, int forwardChannel, int reverseChannel); virtual ~DoubleSolenoid(); virtual void Set(Value value); virtual Value Get() const; @@ -47,10 +46,10 @@ class DoubleSolenoid : public SolenoidBase, std::shared_ptr GetTable() const; private: - uint32_t m_forwardChannel; ///< The forward channel on the module to control. - uint32_t m_reverseChannel; ///< The reverse channel on the module to control. - uint8_t m_forwardMask; ///< The mask for the forward channel. - uint8_t m_reverseMask; ///< The mask for the reverse channel. + int m_forwardChannel; ///< The forward channel on the module to control. + int m_reverseChannel; ///< The reverse channel on the module to control. + int m_forwardMask; ///< The mask for the forward channel. + int m_reverseMask; ///< The mask for the reverse channel. HAL_SolenoidHandle m_forwardHandle = HAL_kInvalidHandle; HAL_SolenoidHandle m_reverseHandle = HAL_kInvalidHandle; diff --git a/wpilibc/athena/include/DriverStation.h b/wpilibc/athena/include/DriverStation.h index 948945f06f..14f7755e50 100644 --- a/wpilibc/athena/include/DriverStation.h +++ b/wpilibc/athena/include/DriverStation.h @@ -34,25 +34,25 @@ class DriverStation : public SensorBase, public RobotStateInterface { static DriverStation& GetInstance(); static void ReportError(std::string error); static void ReportWarning(std::string error); - static void ReportError(bool is_error, int32_t code, const std::string& error, + static void ReportError(bool is_error, int code, const std::string& error, const std::string& location, const std::string& stack); - static const uint32_t kJoystickPorts = 6; + static const int kJoystickPorts = 6; - float GetStickAxis(uint32_t stick, uint32_t axis); - int GetStickPOV(uint32_t stick, uint32_t pov); - uint32_t GetStickButtons(uint32_t stick) const; - bool GetStickButton(uint32_t stick, uint8_t button); + float GetStickAxis(int stick, int axis); + int GetStickPOV(int stick, int pov); + int GetStickButtons(int stick) const; + bool GetStickButton(int stick, int button); - int GetStickAxisCount(uint32_t stick) const; - int GetStickPOVCount(uint32_t stick) const; - int GetStickButtonCount(uint32_t stick) const; + int GetStickAxisCount(int stick) const; + int GetStickPOVCount(int stick) const; + int GetStickButtonCount(int stick) const; - bool GetJoystickIsXbox(uint32_t stick) const; - int GetJoystickType(uint32_t stick) const; - std::string GetJoystickName(uint32_t stick) const; - int GetJoystickAxisType(uint32_t stick, uint8_t axis) const; + bool GetJoystickIsXbox(int stick) const; + int GetJoystickType(int stick) const; + std::string GetJoystickName(int stick) const; + int GetJoystickAxisType(int stick, int axis) const; bool IsEnabled() const override; bool IsDisabled() const override; @@ -66,7 +66,7 @@ class DriverStation : public SensorBase, public RobotStateInterface { bool IsBrownedOut() const; Alliance GetAlliance() const; - uint32_t GetLocation() const; + int GetLocation() const; void WaitForData(); double GetMatchTime() const; float GetBatteryVoltage() const; diff --git a/wpilibc/athena/include/Encoder.h b/wpilibc/athena/include/Encoder.h index f38f13be19..441d2b26f1 100644 --- a/wpilibc/athena/include/Encoder.h +++ b/wpilibc/athena/include/Encoder.h @@ -46,7 +46,7 @@ class Encoder : public SensorBase, kResetOnRisingEdge }; - Encoder(uint32_t aChannel, uint32_t bChannel, bool reverseDirection = false, + Encoder(int aChannel, int bChannel, bool reverseDirection = false, EncodingType encodingType = k4X); Encoder(std::shared_ptr aSource, std::shared_ptr bSource, bool reverseDirection = false, @@ -58,9 +58,9 @@ class Encoder : public SensorBase, virtual ~Encoder(); // CounterBase interface - int32_t Get() const override; - int32_t GetRaw() const; - int32_t GetEncodingScale() const; + int Get() const override; + int GetRaw() const; + int GetEncodingScale() const; void Reset() override; double GetPeriod() const override; void SetMaxPeriod(double maxPeriod) override; @@ -76,7 +76,7 @@ class Encoder : public SensorBase, int GetSamplesToAverage() const; double PIDGet() override; - void SetIndexSource(uint32_t channel, IndexingType type = kResetOnRisingEdge); + void SetIndexSource(int channel, IndexingType type = kResetOnRisingEdge); DEPRECATED("Use pass-by-reference instead.") void SetIndexSource(DigitalSource* source, IndexingType type = kResetOnRisingEdge); @@ -90,7 +90,7 @@ class Encoder : public SensorBase, void InitTable(std::shared_ptr subTable) override; std::shared_ptr GetTable() const override; - int32_t GetFPGAIndex() const; + int GetFPGAIndex() const; private: void InitEncoder(bool reverseDirection, EncodingType encodingType); diff --git a/wpilibc/athena/include/GearTooth.h b/wpilibc/athena/include/GearTooth.h index 1ef6064dbb..187140b206 100644 --- a/wpilibc/athena/include/GearTooth.h +++ b/wpilibc/athena/include/GearTooth.h @@ -22,7 +22,7 @@ class GearTooth : public Counter { public: /// 55 uSec for threshold static constexpr double kGearToothThreshold = 55e-6; - explicit GearTooth(uint32_t channel, bool directionSensitive = false); + explicit GearTooth(int channel, bool directionSensitive = false); explicit GearTooth(DigitalSource* source, bool directionSensitive = false); explicit GearTooth(std::shared_ptr source, bool directionSensitive = false); diff --git a/wpilibc/athena/include/I2C.h b/wpilibc/athena/include/I2C.h index 8542db307d..433c917789 100644 --- a/wpilibc/athena/include/I2C.h +++ b/wpilibc/athena/include/I2C.h @@ -20,24 +20,23 @@ class I2C : SensorBase { public: enum Port { kOnboard, kMXP }; - I2C(Port port, uint8_t deviceAddress); + I2C(Port port, int deviceAddress); virtual ~I2C(); I2C(const I2C&) = delete; I2C& operator=(const I2C&) = delete; - bool Transaction(uint8_t* dataToSend, uint8_t sendSize, uint8_t* dataReceived, - uint8_t receiveSize); + bool Transaction(uint8_t* dataToSend, int sendSize, uint8_t* dataReceived, + int receiveSize); bool AddressOnly(); - bool Write(uint8_t registerAddress, uint8_t data); - bool WriteBulk(uint8_t* data, uint8_t count); - bool Read(uint8_t registerAddress, uint8_t count, uint8_t* data); - bool ReadOnly(uint8_t count, uint8_t* buffer); - void Broadcast(uint8_t registerAddress, uint8_t data); - bool VerifySensor(uint8_t registerAddress, uint8_t count, - const uint8_t* expected); + bool Write(int registerAddress, uint8_t data); + bool WriteBulk(uint8_t* data, int count); + bool Read(int registerAddress, int count, uint8_t* data); + bool ReadOnly(int count, uint8_t* buffer); + void Broadcast(int registerAddress, uint8_t data); + bool VerifySensor(int registerAddress, int count, const uint8_t* expected); private: Port m_port; - uint8_t m_deviceAddress; + int m_deviceAddress; }; diff --git a/wpilibc/athena/include/Jaguar.h b/wpilibc/athena/include/Jaguar.h index 34b1cd91a9..7e5395bf04 100644 --- a/wpilibc/athena/include/Jaguar.h +++ b/wpilibc/athena/include/Jaguar.h @@ -14,6 +14,6 @@ */ class Jaguar : public PWMSpeedController { public: - explicit Jaguar(uint32_t channel); + explicit Jaguar(int channel); virtual ~Jaguar() = default; }; diff --git a/wpilibc/athena/include/Joystick.h b/wpilibc/athena/include/Joystick.h index ac3b1bc83d..75f09b536f 100644 --- a/wpilibc/athena/include/Joystick.h +++ b/wpilibc/athena/include/Joystick.h @@ -27,11 +27,11 @@ class DriverStation; */ class Joystick : public GenericHID, public ErrorBase { public: - static const uint32_t kDefaultXAxis = 0; - static const uint32_t kDefaultYAxis = 1; - static const uint32_t kDefaultZAxis = 2; - static const uint32_t kDefaultTwistAxis = 2; - static const uint32_t kDefaultThrottleAxis = 3; + static const int kDefaultXAxis = 0; + static const int kDefaultYAxis = 1; + static const int kDefaultZAxis = 2; + static const int kDefaultTwistAxis = 2; + static const int kDefaultThrottleAxis = 3; typedef enum { kXAxis, kYAxis, @@ -40,8 +40,8 @@ class Joystick : public GenericHID, public ErrorBase { kThrottleAxis, kNumAxisTypes } AxisType; - static const uint32_t kDefaultTriggerButton = 1; - static const uint32_t kDefaultTopButton = 2; + static const int kDefaultTriggerButton = 1; + static const int kDefaultTopButton = 2; typedef enum { kTriggerButton, kTopButton, kNumButtonTypes } ButtonType; typedef enum { kLeftRumble, kRightRumble } RumbleType; typedef enum { @@ -63,15 +63,15 @@ class Joystick : public GenericHID, public ErrorBase { kHIDFlight = 23, kHID1stPerson = 24 } HIDType; - explicit Joystick(uint32_t port); - Joystick(uint32_t port, uint32_t numAxisTypes, uint32_t numButtonTypes); + explicit Joystick(int port); + Joystick(int port, int numAxisTypes, int numButtonTypes); virtual ~Joystick() = default; Joystick(const Joystick&) = delete; Joystick& operator=(const Joystick&) = delete; - uint32_t GetAxisChannel(AxisType axis) const; - void SetAxisChannel(AxisType axis, uint32_t channel); + 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; @@ -79,15 +79,15 @@ class Joystick : public GenericHID, public ErrorBase { float GetTwist() const override; float GetThrottle() const override; virtual float GetAxis(AxisType axis) const; - float GetRawAxis(uint32_t axis) const override; + float GetRawAxis(int axis) const override; bool GetTrigger(JoystickHand hand = kRightHand) const override; bool GetTop(JoystickHand hand = kRightHand) const override; bool GetBumper(JoystickHand hand = kRightHand) const override; - bool GetRawButton(uint32_t button) const override; - int GetPOV(uint32_t pov = 0) const override; + bool GetRawButton(int button) const override; + int GetPOV(int pov = 0) const override; bool GetButton(ButtonType button) const; - static Joystick* GetStickForPort(uint32_t port); + static Joystick* GetStickForPort(int port); virtual float GetMagnitude() const; virtual float GetDirectionRadians() const; @@ -104,15 +104,15 @@ class Joystick : public GenericHID, public ErrorBase { int GetPOVCount() const; void SetRumble(RumbleType type, float value); - void SetOutput(uint8_t outputNumber, bool value); - void SetOutputs(uint32_t value); + void SetOutput(int outputNumber, bool value); + void SetOutputs(int value); private: DriverStation& m_ds; - uint32_t m_port; - std::vector m_axes; - std::vector m_buttons; - uint32_t m_outputs = 0; + int m_port; + std::vector m_axes; + std::vector m_buttons; + int m_outputs = 0; uint16_t m_leftRumble = 0; uint16_t m_rightRumble = 0; }; diff --git a/wpilibc/athena/include/PWM.h b/wpilibc/athena/include/PWM.h index 64172251c5..3a5029befc 100644 --- a/wpilibc/athena/include/PWM.h +++ b/wpilibc/athena/include/PWM.h @@ -42,7 +42,7 @@ class PWM : public SensorBase, kPeriodMultiplier_4X = 4 }; - explicit PWM(uint32_t channel); + explicit PWM(int channel); virtual ~PWM(); virtual void SetRaw(uint16_t value); virtual uint16_t GetRaw() const; @@ -56,11 +56,11 @@ class PWM : public SensorBase, void EnableDeadbandElimination(bool eliminateDeadband); void SetBounds(float max, float deadbandMax, float center, float deadbandMin, float min); - void SetRawBounds(int32_t max, int32_t deadbandMax, int32_t center, - int32_t deadbandMin, int32_t min); + void SetRawBounds(int max, int deadbandMax, int center, int deadbandMin, + int min); void GetRawBounds(int32_t* max, int32_t* deadbandMax, int32_t* center, int32_t* deadbandMin, int32_t* min); - uint32_t GetChannel() const { return m_channel; } + int GetChannel() const { return m_channel; } protected: void ValueChanged(ITable* source, llvm::StringRef key, @@ -75,6 +75,6 @@ class PWM : public SensorBase, std::shared_ptr m_table; private: - uint32_t m_channel; + int m_channel; HAL_DigitalHandle m_handle; }; diff --git a/wpilibc/athena/include/PWMSpeedController.h b/wpilibc/athena/include/PWMSpeedController.h index 96a9b52178..c4b0b0e5a2 100644 --- a/wpilibc/athena/include/PWMSpeedController.h +++ b/wpilibc/athena/include/PWMSpeedController.h @@ -27,7 +27,7 @@ class PWMSpeedController : public SafePWM, public SpeedController { bool GetInverted() const override; protected: - explicit PWMSpeedController(uint32_t channel); + explicit PWMSpeedController(int channel); private: bool m_isInverted = false; diff --git a/wpilibc/athena/include/PowerDistributionPanel.h b/wpilibc/athena/include/PowerDistributionPanel.h index 15b19b479d..b659fc2fc7 100644 --- a/wpilibc/athena/include/PowerDistributionPanel.h +++ b/wpilibc/athena/include/PowerDistributionPanel.h @@ -20,11 +20,11 @@ class PowerDistributionPanel : public SensorBase, public LiveWindowSendable { public: PowerDistributionPanel(); - explicit PowerDistributionPanel(uint8_t module); + explicit PowerDistributionPanel(int module); float GetVoltage() const; float GetTemperature() const; - float GetCurrent(uint8_t channel) const; + float GetCurrent(int channel) const; float GetTotalCurrent() const; float GetTotalPower() const; float GetTotalEnergy() const; @@ -40,5 +40,5 @@ class PowerDistributionPanel : public SensorBase, public LiveWindowSendable { private: std::shared_ptr m_table; - uint8_t m_module; + int m_module; }; diff --git a/wpilibc/athena/include/Preferences.h b/wpilibc/athena/include/Preferences.h index 43f920056d..2a7a49c09e 100644 --- a/wpilibc/athena/include/Preferences.h +++ b/wpilibc/athena/include/Preferences.h @@ -66,7 +66,7 @@ class Preferences : public ErrorBase { std::shared_ptr value, bool isNew) override; void ValueChangedEx(ITable* source, llvm::StringRef key, std::shared_ptr value, - unsigned int flags) override; + uint32_t flags) override; }; Listener m_listener; }; diff --git a/wpilibc/athena/include/Relay.h b/wpilibc/athena/include/Relay.h index b63a61d182..a8239e58dc 100644 --- a/wpilibc/athena/include/Relay.h +++ b/wpilibc/athena/include/Relay.h @@ -38,12 +38,12 @@ class Relay : public MotorSafety, enum Value { kOff, kOn, kForward, kReverse }; enum Direction { kBothDirections, kForwardOnly, kReverseOnly }; - explicit Relay(uint32_t channel, Direction direction = kBothDirections); + explicit Relay(int channel, Direction direction = kBothDirections); virtual ~Relay(); void Set(Value value); Value Get() const; - uint32_t GetChannel() const; + int GetChannel() const; void SetExpiration(float timeout) override; float GetExpiration() const override; @@ -65,7 +65,7 @@ class Relay : public MotorSafety, std::shared_ptr m_table; private: - uint32_t m_channel; + int m_channel; Direction m_direction; HAL_RelayHandle m_forwardHandle = HAL_kInvalidHandle; diff --git a/wpilibc/athena/include/RobotDrive.h b/wpilibc/athena/include/RobotDrive.h index 1780f3656e..f85103895e 100644 --- a/wpilibc/athena/include/RobotDrive.h +++ b/wpilibc/athena/include/RobotDrive.h @@ -36,9 +36,9 @@ class RobotDrive : public MotorSafety, public ErrorBase { kRearRightMotor = 3 }; - RobotDrive(uint32_t leftMotorChannel, uint32_t rightMotorChannel); - RobotDrive(uint32_t frontLeftMotorChannel, uint32_t rearLeftMotorChannel, - uint32_t frontRightMotorChannel, uint32_t rearRightMotorChannel); + RobotDrive(int leftMotorChannel, int rightMotorChannel); + RobotDrive(int frontLeftMotorChannel, int rearLeftMotorChannel, + int frontRightMotorChannel, int rearRightMotorChannel); RobotDrive(SpeedController* leftMotor, SpeedController* rightMotor); RobotDrive(SpeedController& leftMotor, SpeedController& rightMotor); RobotDrive(std::shared_ptr leftMotor, @@ -61,20 +61,18 @@ class RobotDrive : public MotorSafety, public ErrorBase { bool squaredInputs = true); void TankDrive(GenericHID& leftStick, GenericHID& rightStick, bool squaredInputs = true); - void TankDrive(GenericHID* leftStick, uint32_t leftAxis, - GenericHID* rightStick, uint32_t rightAxis, - bool squaredInputs = true); - void TankDrive(GenericHID& leftStick, uint32_t leftAxis, - GenericHID& rightStick, uint32_t rightAxis, - bool squaredInputs = true); + void TankDrive(GenericHID* leftStick, int leftAxis, GenericHID* rightStick, + 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 ArcadeDrive(GenericHID* stick, bool squaredInputs = true); void ArcadeDrive(GenericHID& stick, bool squaredInputs = true); - void ArcadeDrive(GenericHID* moveStick, uint32_t moveChannel, - GenericHID* rotateStick, uint32_t rotateChannel, + void ArcadeDrive(GenericHID* moveStick, int moveChannel, + GenericHID* rotateStick, int rotateChannel, bool squaredInputs = true); - void ArcadeDrive(GenericHID& moveStick, uint32_t moveChannel, - GenericHID& rotateStick, uint32_t rotateChannel, + void ArcadeDrive(GenericHID& moveStick, int moveChannel, + GenericHID& rotateStick, int rotateChannel, bool squaredInputs = true); void ArcadeDrive(float moveValue, float rotateValue, bool squaredInputs = true); @@ -101,7 +99,7 @@ class RobotDrive : public MotorSafety, public ErrorBase { void Normalize(double* wheelSpeeds); void RotateVector(double& x, double& y, double angle); - static const int32_t kMaxNumberOfMotors = 4; + static const int kMaxNumberOfMotors = 4; float m_sensitivity = 0.5; double m_maxOutput = 1.0; std::shared_ptr m_frontLeftMotor; @@ -111,7 +109,7 @@ class RobotDrive : public MotorSafety, public ErrorBase { std::unique_ptr m_safetyHelper; private: - int32_t GetNumMotors() { + int GetNumMotors() { int motors = 0; if (m_frontLeftMotor) motors++; if (m_frontRightMotor) motors++; diff --git a/wpilibc/athena/include/SD540.h b/wpilibc/athena/include/SD540.h index 94a1734859..9d701e0c58 100644 --- a/wpilibc/athena/include/SD540.h +++ b/wpilibc/athena/include/SD540.h @@ -14,6 +14,6 @@ */ class SD540 : public PWMSpeedController { public: - explicit SD540(uint32_t channel); + explicit SD540(int channel); virtual ~SD540() = default; }; diff --git a/wpilibc/athena/include/SPI.h b/wpilibc/athena/include/SPI.h index 9a16c04947..8f51385249 100644 --- a/wpilibc/athena/include/SPI.h +++ b/wpilibc/athena/include/SPI.h @@ -42,27 +42,25 @@ class SPI : public SensorBase { void SetChipSelectActiveHigh(); void SetChipSelectActiveLow(); - virtual int32_t Write(uint8_t* data, uint8_t size); - virtual int32_t Read(bool initiate, uint8_t* dataReceived, uint8_t size); - virtual int32_t Transaction(uint8_t* dataToSend, uint8_t* dataReceived, - uint8_t size); + virtual int Write(uint8_t* data, int size); + virtual int Read(bool initiate, uint8_t* dataReceived, int size); + virtual int Transaction(uint8_t* dataToSend, uint8_t* dataReceived, int size); - void InitAccumulator(double period, uint32_t cmd, uint8_t xfer_size, - uint32_t valid_mask, uint32_t valid_value, - uint8_t data_shift, uint8_t data_size, bool is_signed, - bool big_endian); + void InitAccumulator(double period, int cmd, int xfer_size, int valid_mask, + int valid_value, int data_shift, int data_size, + bool is_signed, bool big_endian); void FreeAccumulator(); void ResetAccumulator(); - void SetAccumulatorCenter(int32_t center); - void SetAccumulatorDeadband(int32_t deadband); - int32_t GetAccumulatorLastValue() const; + void SetAccumulatorCenter(int center); + void SetAccumulatorDeadband(int deadband); + int GetAccumulatorLastValue() const; int64_t GetAccumulatorValue() const; int64_t GetAccumulatorCount() const; double GetAccumulatorAverage() const; void GetAccumulatorOutput(int64_t& value, int64_t& count) const; protected: - uint8_t m_port; + int m_port; bool m_msbFirst = false; // default little-endian bool m_sampleOnTrailing = false; // default data updated on falling edge bool m_clk_idle_high = false; // default clock active high diff --git a/wpilibc/athena/include/SafePWM.h b/wpilibc/athena/include/SafePWM.h index f12096234b..3dc6cc3157 100644 --- a/wpilibc/athena/include/SafePWM.h +++ b/wpilibc/athena/include/SafePWM.h @@ -23,7 +23,7 @@ */ class SafePWM : public PWM, public MotorSafety { public: - explicit SafePWM(uint32_t channel); + explicit SafePWM(int channel); virtual ~SafePWM() = default; void SetExpiration(float timeout); diff --git a/wpilibc/athena/include/SerialPort.h b/wpilibc/athena/include/SerialPort.h index a4eff69a41..da3f1cc808 100644 --- a/wpilibc/athena/include/SerialPort.h +++ b/wpilibc/athena/include/SerialPort.h @@ -46,7 +46,7 @@ class SerialPort : public ErrorBase { enum WriteBufferMode { kFlushOnAccess = 1, kFlushWhenFull = 2 }; enum Port { kOnboard = 0, kMXP = 1, kUSB = 2 }; - SerialPort(uint32_t baudRate, Port port = kOnboard, uint8_t dataBits = 8, + SerialPort(int baudRate, Port port = kOnboard, int dataBits = 8, Parity parity = kParity_None, StopBits stopBits = kStopBits_One); ~SerialPort(); @@ -56,19 +56,19 @@ class SerialPort : public ErrorBase { void SetFlowControl(FlowControl flowControl); void EnableTermination(char terminator = '\n'); void DisableTermination(); - int32_t GetBytesReceived(); - uint32_t Read(char* buffer, int32_t count); - uint32_t Write(const std::string& buffer, int32_t count); + int GetBytesReceived(); + int Read(char* buffer, int count); + int Write(const std::string& buffer, int count); void SetTimeout(float timeout); - void SetReadBufferSize(uint32_t size); - void SetWriteBufferSize(uint32_t size); + void SetReadBufferSize(int size); + void SetWriteBufferSize(int size); void SetWriteBufferMode(WriteBufferMode mode); void Flush(); void Reset(); private: - uint32_t m_resourceManagerHandle = 0; - uint32_t m_portHandle = 0; + int m_resourceManagerHandle = 0; + int m_portHandle = 0; bool m_consoleModeEnabled = false; - uint8_t m_port; + int m_port; }; diff --git a/wpilibc/athena/include/Servo.h b/wpilibc/athena/include/Servo.h index 1d949b0538..0c69fe8fa1 100644 --- a/wpilibc/athena/include/Servo.h +++ b/wpilibc/athena/include/Servo.h @@ -22,7 +22,7 @@ */ class Servo : public SafePWM { public: - explicit Servo(uint32_t channel); + explicit Servo(int channel); virtual ~Servo(); void Set(float value); void SetOffline(); diff --git a/wpilibc/athena/include/Solenoid.h b/wpilibc/athena/include/Solenoid.h index 2110985578..672cddbb99 100644 --- a/wpilibc/athena/include/Solenoid.h +++ b/wpilibc/athena/include/Solenoid.h @@ -25,8 +25,8 @@ class Solenoid : public SolenoidBase, public LiveWindowSendable, public ITableListener { public: - explicit Solenoid(uint32_t channel); - Solenoid(uint8_t moduleNumber, uint32_t channel); + explicit Solenoid(int channel); + Solenoid(int moduleNumber, int channel); virtual ~Solenoid(); virtual void Set(bool on); virtual bool Get() const; @@ -43,6 +43,6 @@ class Solenoid : public SolenoidBase, private: HAL_SolenoidHandle m_solenoidHandle = HAL_kInvalidHandle; - uint32_t m_channel; ///< The channel on the module to control. + int m_channel; ///< The channel on the module to control. std::shared_ptr m_table; }; diff --git a/wpilibc/athena/include/SolenoidBase.h b/wpilibc/athena/include/SolenoidBase.h index 5585645c0d..d217122659 100644 --- a/wpilibc/athena/include/SolenoidBase.h +++ b/wpilibc/athena/include/SolenoidBase.h @@ -18,18 +18,18 @@ class SolenoidBase : public SensorBase { public: virtual ~SolenoidBase() = default; - uint8_t GetAll(int module = 0) const; + int GetAll(int module = 0) const; - uint8_t GetPCMSolenoidBlackList(int module) const; + int GetPCMSolenoidBlackList(int module) const; bool GetPCMSolenoidVoltageStickyFault(int module) const; bool GetPCMSolenoidVoltageFault(int module) const; void ClearAllPCMStickyFaults(int module); protected: - explicit SolenoidBase(uint8_t pcmID); + explicit SolenoidBase(int pcmID); static const int m_maxModules = 63; static const int m_maxPorts = 8; // static void* m_ports[m_maxModules][m_maxPorts]; - uint8_t m_moduleNumber; ///< Slot number where the module is plugged into - /// the chassis. + int m_moduleNumber; ///< Slot number where the module is plugged into + /// the chassis. }; diff --git a/wpilibc/athena/include/Spark.h b/wpilibc/athena/include/Spark.h index af5fafeb9a..2f9de3d61a 100644 --- a/wpilibc/athena/include/Spark.h +++ b/wpilibc/athena/include/Spark.h @@ -14,6 +14,6 @@ */ class Spark : public PWMSpeedController { public: - explicit Spark(uint32_t channel); + explicit Spark(int channel); virtual ~Spark() = default; }; diff --git a/wpilibc/athena/include/Talon.h b/wpilibc/athena/include/Talon.h index 6205acca8e..b39e2a6ed8 100644 --- a/wpilibc/athena/include/Talon.h +++ b/wpilibc/athena/include/Talon.h @@ -14,6 +14,6 @@ */ class Talon : public PWMSpeedController { public: - explicit Talon(uint32_t channel); + explicit Talon(int channel); virtual ~Talon() = default; }; diff --git a/wpilibc/athena/include/TalonSRX.h b/wpilibc/athena/include/TalonSRX.h index 78725c339f..177710e589 100644 --- a/wpilibc/athena/include/TalonSRX.h +++ b/wpilibc/athena/include/TalonSRX.h @@ -15,6 +15,6 @@ */ class TalonSRX : public PWMSpeedController { public: - explicit TalonSRX(uint32_t channel); + explicit TalonSRX(int channel); virtual ~TalonSRX() = default; }; diff --git a/wpilibc/athena/include/USBCamera.h b/wpilibc/athena/include/USBCamera.h index 5cf247687c..a4545c03f7 100644 --- a/wpilibc/athena/include/USBCamera.h +++ b/wpilibc/athena/include/USBCamera.h @@ -50,19 +50,19 @@ class USBCamera : public ErrorBase { priority_recursive_mutex m_mutex; - unsigned int m_width = 320; - unsigned int m_height = 240; + int m_width = 320; + int m_height = 240; double m_fps = 30; std::string m_whiteBalance = AUTO; - unsigned int m_whiteBalanceValue = 0; + int m_whiteBalanceValue = 0; bool m_whiteBalanceValuePresent = false; std::string m_exposure = MANUAL; - unsigned int m_exposureValue = 50; + int m_exposureValue = 50; bool m_exposureValuePresent = false; - unsigned int m_brightness = 80; + int m_brightness = 80; bool m_needSettingsUpdate = true; - unsigned int GetJpegSize(void* buffer, unsigned int buffSize); + int GetJpegSize(void* buffer, int buffSize); public: static constexpr char const* kDefaultCameraName = "cam0"; @@ -74,18 +74,18 @@ class USBCamera : public ErrorBase { void StartCapture(); void StopCapture(); void SetFPS(double fps); - void SetSize(unsigned int width, unsigned int height); + void SetSize(int width, int height); void UpdateSettings(); /** * Set the brightness, as a percentage (0-100). */ - void SetBrightness(unsigned int brightness); + void SetBrightness(int brightness); /** * Get the brightness, as a percentage (0-100). */ - unsigned int GetBrightness(); + int GetBrightness(); /** * Set the white balance to auto @@ -100,7 +100,7 @@ class USBCamera : public ErrorBase { /** * Set the white balance to manual, with specified color temperature */ - void SetWhiteBalanceManual(unsigned int wbValue); + void SetWhiteBalanceManual(int wbValue); /** * Set the exposure to auto exposure @@ -115,8 +115,8 @@ class USBCamera : public ErrorBase { /** * Set the exposure to manual, with a given percentage (0-100) */ - void SetExposureManual(unsigned int expValue); + void SetExposureManual(int expValue); void GetImage(Image* image); - unsigned int GetImageData(void* buffer, unsigned int bufferSize); + int GetImageData(void* buffer, int bufferSize); }; diff --git a/wpilibc/athena/include/Ultrasonic.h b/wpilibc/athena/include/Ultrasonic.h index 213db2d952..b363a23d66 100644 --- a/wpilibc/athena/include/Ultrasonic.h +++ b/wpilibc/athena/include/Ultrasonic.h @@ -47,8 +47,7 @@ class Ultrasonic : public SensorBase, Ultrasonic(std::shared_ptr pingChannel, std::shared_ptr echoChannel, DistanceUnit units = kInches); - Ultrasonic(uint32_t pingChannel, uint32_t echoChannel, - DistanceUnit units = kInches); + Ultrasonic(int pingChannel, int echoChannel, DistanceUnit units = kInches); virtual ~Ultrasonic(); void Ping(); @@ -79,7 +78,7 @@ class Ultrasonic : public SensorBase, // Time (sec) for the ping trigger pulse. static constexpr double kPingTime = 10 * 1e-6; // Priority that the ultrasonic round robin task runs. - static const uint32_t kPriority = 64; + static const int kPriority = 64; // Max time (ms) between readings. static constexpr double kMaxUltrasonicTime = 0.1; static constexpr double kSpeedOfSoundInchesPerSec = 1130.0 * 12.0; diff --git a/wpilibc/athena/include/Victor.h b/wpilibc/athena/include/Victor.h index 9abc828213..51d9da4412 100644 --- a/wpilibc/athena/include/Victor.h +++ b/wpilibc/athena/include/Victor.h @@ -17,6 +17,6 @@ */ class Victor : public PWMSpeedController { public: - explicit Victor(uint32_t channel); + explicit Victor(int channel); virtual ~Victor() = default; }; diff --git a/wpilibc/athena/include/VictorSP.h b/wpilibc/athena/include/VictorSP.h index bc75e7fc63..2f8ac63300 100644 --- a/wpilibc/athena/include/VictorSP.h +++ b/wpilibc/athena/include/VictorSP.h @@ -14,6 +14,6 @@ */ class VictorSP : public PWMSpeedController { public: - explicit VictorSP(uint32_t channel); + explicit VictorSP(int channel); virtual ~VictorSP() = default; }; diff --git a/wpilibc/athena/include/Vision/AxisCamera.h b/wpilibc/athena/include/Vision/AxisCamera.h index ad7e48b4a2..2e96688a32 100644 --- a/wpilibc/athena/include/Vision/AxisCamera.h +++ b/wpilibc/athena/include/Vision/AxisCamera.h @@ -61,8 +61,7 @@ class AxisCamera : public ErrorBase { int GetImage(Image* image); int GetImage(ColorImage* image); HSLImage* GetImage(); - int CopyJPEG(char** destImage, unsigned int& destImageSize, - unsigned int& destImageBufferSize); + int CopyJPEG(char** destImage, int& destImageSize, int& destImageBufferSize); void WriteBrightness(int brightness); int GetBrightness(); diff --git a/wpilibc/athena/include/Vision/BaeUtilities.h b/wpilibc/athena/include/Vision/BaeUtilities.h index 40c3ed7bd4..01d45a9f00 100644 --- a/wpilibc/athena/include/Vision/BaeUtilities.h +++ b/wpilibc/athena/include/Vision/BaeUtilities.h @@ -7,6 +7,8 @@ #pragma once +#include + #include /* Constants */ diff --git a/wpilibc/athena/include/Vision/FrcError.h b/wpilibc/athena/include/Vision/FrcError.h index bfe0748d1b..664f0beefb 100644 --- a/wpilibc/athena/include/Vision/FrcError.h +++ b/wpilibc/athena/include/Vision/FrcError.h @@ -7,6 +7,8 @@ #pragma once +#include + /* Error Codes */ #define ERR_VISION_GENERAL_ERROR 166000 // #define ERR_COLOR_NOT_FOUND 166100 // TrackAPI.cpp diff --git a/wpilibc/athena/include/Vision/Threshold.h b/wpilibc/athena/include/Vision/Threshold.h index 78d82b44f5..7236cea404 100644 --- a/wpilibc/athena/include/Vision/Threshold.h +++ b/wpilibc/athena/include/Vision/Threshold.h @@ -7,6 +7,8 @@ #pragma once +#include + /** * Color threshold values. * This object represnts the threshold values for any type of color object diff --git a/wpilibc/athena/include/Vision/VisionAPI.h b/wpilibc/athena/include/Vision/VisionAPI.h index c761f27c77..91bdc883fc 100644 --- a/wpilibc/athena/include/Vision/VisionAPI.h +++ b/wpilibc/athena/include/Vision/VisionAPI.h @@ -7,6 +7,8 @@ #pragma once +#include + #include "nivision.h" /* Constants */ @@ -142,14 +144,13 @@ int frcColorEqualize(Image* dest, const Image* source, int colorEqualization); /* Image Thresholding & Conversion functions */ /* Smart Threshold: calls imaqLocalThreshold */ -int frcSmartThreshold(Image* dest, const Image* source, - unsigned int windowWidth, unsigned int windowHeight, - LocalThresholdMethod method, double deviationWeight, - ObjectType type); -int frcSmartThreshold(Image* dest, const Image* source, - unsigned int windowWidth, unsigned int windowHeight, - LocalThresholdMethod method, double deviationWeight, - ObjectType type, float replaceValue); +int frcSmartThreshold(Image* dest, const Image* source, int windowWidth, + int windowHeight, LocalThresholdMethod method, + double deviationWeight, ObjectType type); +int frcSmartThreshold(Image* dest, const Image* source, int windowWidth, + int windowHeight, LocalThresholdMethod method, + double deviationWeight, ObjectType type, + float replaceValue); /* Simple Threshold: calls imaqThreshold */ int frcSimpleThreshold(Image* dest, const Image* source, float rangeMin, diff --git a/wpilibc/athena/include/WPILib.h b/wpilibc/athena/include/WPILib.h index 2a8e7b1eba..33ddc84f1f 100644 --- a/wpilibc/athena/include/WPILib.h +++ b/wpilibc/athena/include/WPILib.h @@ -65,7 +65,6 @@ #include "PowerDistributionPanel.h" #include "Preferences.h" #include "Relay.h" -#include "Resource.h" #include "RobotBase.h" #include "RobotDrive.h" #include "SD540.h" diff --git a/wpilibc/athena/src/ADXL345_I2C.cpp b/wpilibc/athena/src/ADXL345_I2C.cpp index 92eee73016..b0d7d6b860 100644 --- a/wpilibc/athena/src/ADXL345_I2C.cpp +++ b/wpilibc/athena/src/ADXL345_I2C.cpp @@ -10,10 +10,10 @@ #include "I2C.h" #include "LiveWindow/LiveWindow.h" -const uint8_t ADXL345_I2C::kAddress; -const uint8_t ADXL345_I2C::kPowerCtlRegister; -const uint8_t ADXL345_I2C::kDataFormatRegister; -const uint8_t ADXL345_I2C::kDataRegister; +const int ADXL345_I2C::kAddress; +const int ADXL345_I2C::kPowerCtlRegister; +const int ADXL345_I2C::kDataFormatRegister; +const int ADXL345_I2C::kDataRegister; constexpr double ADXL345_I2C::kGsPerLSB; /** @@ -54,7 +54,7 @@ double ADXL345_I2C::GetZ() { return GetAcceleration(kAxis_Z); } */ double ADXL345_I2C::GetAcceleration(ADXL345_I2C::Axes axis) { int16_t rawAccel = 0; - m_i2c.Read(kDataRegister + static_cast(axis), sizeof(rawAccel), + m_i2c.Read(kDataRegister + static_cast(axis), sizeof(rawAccel), reinterpret_cast(&rawAccel)); return rawAccel * kGsPerLSB; } diff --git a/wpilibc/athena/src/ADXL345_SPI.cpp b/wpilibc/athena/src/ADXL345_SPI.cpp index 91fb3b4c35..097bdd9f4b 100644 --- a/wpilibc/athena/src/ADXL345_SPI.cpp +++ b/wpilibc/athena/src/ADXL345_SPI.cpp @@ -11,9 +11,9 @@ #include "HAL/HAL.h" #include "LiveWindow/LiveWindow.h" -const uint8_t ADXL345_SPI::kPowerCtlRegister; -const uint8_t ADXL345_SPI::kDataFormatRegister; -const uint8_t ADXL345_SPI::kDataRegister; +const int ADXL345_SPI::kPowerCtlRegister; +const int ADXL345_SPI::kDataFormatRegister; +const int ADXL345_SPI::kDataRegister; constexpr double ADXL345_SPI::kGsPerLSB; /** @@ -92,7 +92,7 @@ ADXL345_SPI::AllAxes ADXL345_SPI::GetAccelerations() { dataBuffer[0] = (kAddress_Read | kAddress_MultiByte | kDataRegister); m_spi.Transaction(dataBuffer, dataBuffer, 7); - for (int32_t i = 0; i < 3; i++) { + for (int i = 0; i < 3; i++) { // Sensor is little endian... swap bytes rawData[i] = dataBuffer[i * 2 + 2] << 8 | dataBuffer[i * 2 + 1]; } diff --git a/wpilibc/athena/src/ADXL362.cpp b/wpilibc/athena/src/ADXL362.cpp index 3cfba2c18d..62edbb7e5e 100644 --- a/wpilibc/athena/src/ADXL362.cpp +++ b/wpilibc/athena/src/ADXL362.cpp @@ -12,22 +12,22 @@ #include "HAL/HAL.h" #include "LiveWindow/LiveWindow.h" -static uint8_t kRegWrite = 0x0A; -static uint8_t kRegRead = 0x0B; +static int kRegWrite = 0x0A; +static int kRegRead = 0x0B; -static uint8_t kPartIdRegister = 0x02; -static uint8_t kDataRegister = 0x0E; -static uint8_t kFilterCtlRegister = 0x2C; -static uint8_t kPowerCtlRegister = 0x2D; +static int kPartIdRegister = 0x02; +static int kDataRegister = 0x0E; +static int kFilterCtlRegister = 0x2C; +static int kPowerCtlRegister = 0x2D; -// static uint8_t kFilterCtl_Range2G = 0x00; -// static uint8_t kFilterCtl_Range4G = 0x40; -// static uint8_t kFilterCtl_Range8G = 0x80; -static uint8_t kFilterCtl_ODR_100Hz = 0x03; +// static int kFilterCtl_Range2G = 0x00; +// static int kFilterCtl_Range4G = 0x40; +// static int kFilterCtl_Range8G = 0x80; +static int kFilterCtl_ODR_100Hz = 0x03; -static uint8_t kPowerCtl_UltraLowNoise = 0x20; -// static uint8_t kPowerCtl_AutoSleep = 0x04; -static uint8_t kPowerCtl_Measure = 0x02; +static int kPowerCtl_UltraLowNoise = 0x20; +// static int kPowerCtl_AutoSleep = 0x04; +static int kPowerCtl_Measure = 0x02; /** * Constructor. Uses the onboard CS1. @@ -147,7 +147,7 @@ ADXL362::AllAxes ADXL362::GetAccelerations() { dataBuffer[1] = kDataRegister; m_spi.Transaction(dataBuffer, dataBuffer, 8); - for (int32_t i = 0; i < 3; i++) { + for (int i = 0; i < 3; i++) { // Sensor is little endian... swap bytes rawData[i] = dataBuffer[i * 2 + 3] << 8 | dataBuffer[i * 2 + 2]; } diff --git a/wpilibc/athena/src/ADXRS450_Gyro.cpp b/wpilibc/athena/src/ADXRS450_Gyro.cpp index 17e282584c..aa1f726166 100644 --- a/wpilibc/athena/src/ADXRS450_Gyro.cpp +++ b/wpilibc/athena/src/ADXRS450_Gyro.cpp @@ -14,15 +14,15 @@ static constexpr double kSamplePeriod = 0.001; static constexpr double kCalibrationSampleTime = 5.0; static constexpr double kDegreePerSecondPerLSB = 0.0125; -static constexpr uint8_t kRateRegister = 0x00; -static constexpr uint8_t kTemRegister = 0x02; -static constexpr uint8_t kLoCSTRegister = 0x04; -static constexpr uint8_t kHiCSTRegister = 0x06; -static constexpr uint8_t kQuadRegister = 0x08; -static constexpr uint8_t kFaultRegister = 0x0A; -static constexpr uint8_t kPIDRegister = 0x0C; -static constexpr uint8_t kSNHighRegister = 0x0E; -static constexpr uint8_t kSNLowRegister = 0x10; +static constexpr int kRateRegister = 0x00; +static constexpr int kTemRegister = 0x02; +static constexpr int kLoCSTRegister = 0x04; +static constexpr int kHiCSTRegister = 0x06; +static constexpr int kQuadRegister = 0x08; +static constexpr int kFaultRegister = 0x0A; +static constexpr int kPIDRegister = 0x0C; +static constexpr int kSNHighRegister = 0x0E; +static constexpr int kSNLowRegister = 0x10; /** * Initialize the gyro. @@ -43,8 +43,7 @@ void ADXRS450_Gyro::Calibrate() { Wait(kCalibrationSampleTime); - m_spi.SetAccumulatorCenter( - static_cast(m_spi.GetAccumulatorAverage())); + m_spi.SetAccumulatorCenter(static_cast(m_spi.GetAccumulatorAverage())); m_spi.ResetAccumulator(); } @@ -80,7 +79,7 @@ ADXRS450_Gyro::ADXRS450_Gyro(SPI::Port port) : m_spi(port) { LiveWindow::GetInstance()->AddSensor("ADXRS450_Gyro", port, this); } -static bool CalcParity(uint32_t v) { +static bool CalcParity(int v) { bool parity = false; while (v != 0) { parity = !parity; @@ -89,16 +88,16 @@ static bool CalcParity(uint32_t v) { return parity; } -static inline uint32_t BytesToIntBE(uint8_t* buf) { - uint32_t result = static_cast(buf[0]) << 24; - result |= static_cast(buf[1]) << 16; - result |= static_cast(buf[2]) << 8; - result |= static_cast(buf[3]); +static inline int BytesToIntBE(uint8_t* buf) { + int result = static_cast(buf[0]) << 24; + result |= static_cast(buf[1]) << 16; + result |= static_cast(buf[2]) << 8; + result |= static_cast(buf[3]); return result; } -uint16_t ADXRS450_Gyro::ReadRegister(uint8_t reg) { - uint32_t cmd = 0x80000000 | static_cast(reg) << 17; +uint16_t ADXRS450_Gyro::ReadRegister(int reg) { + int cmd = 0x80000000 | static_cast(reg) << 17; if (!CalcParity(cmd)) cmd |= 1u; // big endian diff --git a/wpilibc/athena/src/AnalogAccelerometer.cpp b/wpilibc/athena/src/AnalogAccelerometer.cpp index e6c076f97f..5bc61dbf1a 100644 --- a/wpilibc/athena/src/AnalogAccelerometer.cpp +++ b/wpilibc/athena/src/AnalogAccelerometer.cpp @@ -28,7 +28,7 @@ void AnalogAccelerometer::InitAccelerometer() { * @param channel The channel number for the analog input the accelerometer is * connected to */ -AnalogAccelerometer::AnalogAccelerometer(int32_t channel) { +AnalogAccelerometer::AnalogAccelerometer(int channel) { m_analogInput = std::make_shared(channel); InitAccelerometer(); } diff --git a/wpilibc/athena/src/AnalogGyro.cpp b/wpilibc/athena/src/AnalogGyro.cpp index e0f6a51801..be40f5ba36 100644 --- a/wpilibc/athena/src/AnalogGyro.cpp +++ b/wpilibc/athena/src/AnalogGyro.cpp @@ -15,8 +15,8 @@ #include "Timer.h" #include "WPIErrors.h" -const uint32_t AnalogGyro::kOversampleBits; -const uint32_t AnalogGyro::kAverageBits; +const int AnalogGyro::kOversampleBits; +const int AnalogGyro::kAverageBits; constexpr float AnalogGyro::kSamplesPerSecond; constexpr float AnalogGyro::kCalibrationSampleTime; constexpr float AnalogGyro::kDefaultVoltsPerDegreePerSecond; @@ -27,7 +27,7 @@ constexpr float AnalogGyro::kDefaultVoltsPerDegreePerSecond; * @param channel The analog channel the gyro is connected to. Gyros can only * be used on on-board Analog Inputs 0-1. */ -AnalogGyro::AnalogGyro(int32_t channel) +AnalogGyro::AnalogGyro(int channel) : AnalogGyro(std::make_shared(channel)) {} /** @@ -76,7 +76,7 @@ AnalogGyro::AnalogGyro(std::shared_ptr channel) * value. * @param offset Preset uncalibrated value to use as the gyro offset. */ -AnalogGyro::AnalogGyro(int32_t channel, uint32_t center, float offset) { +AnalogGyro::AnalogGyro(int channel, int center, float offset) { m_analog = std::make_shared(channel); InitGyro(); int32_t status = 0; @@ -101,7 +101,7 @@ AnalogGyro::AnalogGyro(int32_t channel, uint32_t center, float offset) { * @param channel A pointer to the AnalogInput object that the gyro is * connected to. */ -AnalogGyro::AnalogGyro(std::shared_ptr channel, uint32_t center, +AnalogGyro::AnalogGyro(std::shared_ptr channel, int center, float offset) : m_analog(channel) { if (channel == nullptr) { @@ -239,10 +239,10 @@ float AnalogGyro::GetOffset() const { * * @return the current center value */ -uint32_t AnalogGyro::GetCenter() const { +int AnalogGyro::GetCenter() const { if (StatusIsFatal()) return 0; int32_t status = 0; - uint32_t value = HAL_GetAnalogGyroCenter(m_gyroHandle, &status); + int value = HAL_GetAnalogGyroCenter(m_gyroHandle, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); return value; } diff --git a/wpilibc/athena/src/AnalogInput.cpp b/wpilibc/athena/src/AnalogInput.cpp index f8bd932e13..9e37627a15 100644 --- a/wpilibc/athena/src/AnalogInput.cpp +++ b/wpilibc/athena/src/AnalogInput.cpp @@ -14,9 +14,9 @@ #include "Timer.h" #include "WPIErrors.h" -const uint8_t AnalogInput::kAccumulatorModuleNumber; -const uint32_t AnalogInput::kAccumulatorNumChannels; -const uint32_t AnalogInput::kAccumulatorChannels[] = {0, 1}; +const int AnalogInput::kAccumulatorModuleNumber; +const int AnalogInput::kAccumulatorNumChannels; +const int AnalogInput::kAccumulatorChannels[] = {0, 1}; /** * Construct an analog input. @@ -24,7 +24,7 @@ const uint32_t AnalogInput::kAccumulatorChannels[] = {0, 1}; * @param channel The channel number on the roboRIO to represent. 0-3 are * on-board 4-7 are on the MXP port. */ -AnalogInput::AnalogInput(uint32_t channel) { +AnalogInput::AnalogInput(int channel) { std::stringstream buf; buf << "Analog Input " << channel; @@ -41,7 +41,7 @@ AnalogInput::AnalogInput(uint32_t channel) { if (status != 0) { wpi_setErrorWithContextRange(status, 0, HAL_GetNumAnalogInputs(), channel, HAL_GetErrorMessage(status)); - m_channel = std::numeric_limits::max(); + m_channel = std::numeric_limits::max(); m_port = HAL_kInvalidHandle; return; } @@ -67,10 +67,10 @@ AnalogInput::~AnalogInput() { * * @return A sample straight from this channel. */ -int32_t AnalogInput::GetValue() const { +int AnalogInput::GetValue() const { if (StatusIsFatal()) return 0; int32_t status = 0; - int32_t value = HAL_GetAnalogValue(m_port, &status); + int value = HAL_GetAnalogValue(m_port, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); return value; } @@ -89,10 +89,10 @@ int32_t AnalogInput::GetValue() const { * * @return A sample from the oversample and average engine for this channel. */ -int32_t AnalogInput::GetAverageValue() const { +int AnalogInput::GetAverageValue() const { if (StatusIsFatal()) return 0; int32_t status = 0; - int32_t value = HAL_GetAnalogAverageValue(m_port, &status); + int value = HAL_GetAnalogAverageValue(m_port, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); return value; } @@ -142,10 +142,10 @@ float AnalogInput::GetAverageVoltage() const { * * @return Least significant bit weight. */ -int32_t AnalogInput::GetLSBWeight() const { +int AnalogInput::GetLSBWeight() const { if (StatusIsFatal()) return 0; int32_t status = 0; - int32_t lsbWeight = HAL_GetAnalogLSBWeight(m_port, &status); + int lsbWeight = HAL_GetAnalogLSBWeight(m_port, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); return lsbWeight; } @@ -157,10 +157,10 @@ int32_t AnalogInput::GetLSBWeight() const { * * @return Offset constant. */ -int32_t AnalogInput::GetOffset() const { +int AnalogInput::GetOffset() const { if (StatusIsFatal()) return 0; int32_t status = 0; - int32_t offset = HAL_GetAnalogOffset(m_port, &status); + int offset = HAL_GetAnalogOffset(m_port, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); return offset; } @@ -170,7 +170,7 @@ int32_t AnalogInput::GetOffset() const { * * @return The channel number. */ -uint32_t AnalogInput::GetChannel() const { +int AnalogInput::GetChannel() const { if (StatusIsFatal()) return 0; return m_channel; } @@ -186,7 +186,7 @@ uint32_t AnalogInput::GetChannel() const { * * @param bits Number of bits of averaging. */ -void AnalogInput::SetAverageBits(int32_t bits) { +void AnalogInput::SetAverageBits(int bits) { if (StatusIsFatal()) return; int32_t status = 0; HAL_SetAnalogAverageBits(m_port, bits, &status); @@ -201,9 +201,9 @@ void AnalogInput::SetAverageBits(int32_t bits) { * * @return Number of bits of averaging previously configured. */ -int32_t AnalogInput::GetAverageBits() const { +int AnalogInput::GetAverageBits() const { int32_t status = 0; - int32_t averageBits = HAL_GetAnalogAverageBits(m_port, &status); + int averageBits = HAL_GetAnalogAverageBits(m_port, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); return averageBits; } @@ -218,7 +218,7 @@ int32_t AnalogInput::GetAverageBits() const { * * @param bits Number of bits of oversampling. */ -void AnalogInput::SetOversampleBits(int32_t bits) { +void AnalogInput::SetOversampleBits(int bits) { if (StatusIsFatal()) return; int32_t status = 0; HAL_SetAnalogOversampleBits(m_port, bits, &status); @@ -234,10 +234,10 @@ void AnalogInput::SetOversampleBits(int32_t bits) { * * @return Number of bits of oversampling previously configured. */ -int32_t AnalogInput::GetOversampleBits() const { +int AnalogInput::GetOversampleBits() const { if (StatusIsFatal()) return 0; int32_t status = 0; - int32_t oversampleBits = HAL_GetAnalogOversampleBits(m_port, &status); + int oversampleBits = HAL_GetAnalogOversampleBits(m_port, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); return oversampleBits; } @@ -309,7 +309,7 @@ void AnalogInput::ResetAccumulator() { * source from the accumulator channel. Because of this, any non-zero * oversample bits will affect the size of the value for this field. */ -void AnalogInput::SetAccumulatorCenter(int32_t center) { +void AnalogInput::SetAccumulatorCenter(int center) { if (StatusIsFatal()) return; int32_t status = 0; HAL_SetAccumulatorCenter(m_port, center, &status); @@ -319,7 +319,7 @@ void AnalogInput::SetAccumulatorCenter(int32_t center) { /** * Set the accumulator's deadband. */ -void AnalogInput::SetAccumulatorDeadband(int32_t deadband) { +void AnalogInput::SetAccumulatorDeadband(int deadband) { if (StatusIsFatal()) return; int32_t status = 0; HAL_SetAccumulatorDeadband(m_port, deadband, &status); diff --git a/wpilibc/athena/src/AnalogOutput.cpp b/wpilibc/athena/src/AnalogOutput.cpp index d641f00803..46f5b06b7d 100644 --- a/wpilibc/athena/src/AnalogOutput.cpp +++ b/wpilibc/athena/src/AnalogOutput.cpp @@ -21,13 +21,13 @@ * * @param channel The channel number on the roboRIO to represent. */ -AnalogOutput::AnalogOutput(uint32_t channel) { +AnalogOutput::AnalogOutput(int channel) { std::stringstream buf; buf << "analog input " << channel; if (!SensorBase::CheckAnalogOutputChannel(channel)) { wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf.str()); - m_channel = std::numeric_limits::max(); + m_channel = std::numeric_limits::max(); m_port = HAL_kInvalidHandle; return; } @@ -40,7 +40,7 @@ AnalogOutput::AnalogOutput(uint32_t channel) { if (status != 0) { wpi_setErrorWithContextRange(status, 0, HAL_GetNumAnalogOutputs(), channel, HAL_GetErrorMessage(status)); - m_channel = std::numeric_limits::max(); + m_channel = std::numeric_limits::max(); m_port = HAL_kInvalidHandle; return; } diff --git a/wpilibc/athena/src/AnalogTrigger.cpp b/wpilibc/athena/src/AnalogTrigger.cpp index 85d097d6a0..b27e103d95 100644 --- a/wpilibc/athena/src/AnalogTrigger.cpp +++ b/wpilibc/athena/src/AnalogTrigger.cpp @@ -19,7 +19,7 @@ * @param channel The channel number on the roboRIO to represent. 0-3 are * on-board 4-7 are on the MXP port. */ -AnalogTrigger::AnalogTrigger(int32_t channel) +AnalogTrigger::AnalogTrigger(int channel) : AnalogTrigger(new AnalogInput(channel)) { m_ownsAnalog = true; } @@ -35,11 +35,11 @@ AnalogTrigger::AnalogTrigger(int32_t channel) AnalogTrigger::AnalogTrigger(AnalogInput* input) { m_analogInput = input; int32_t status = 0; - int32_t index = 0; + int index = 0; m_trigger = HAL_InitializeAnalogTrigger(input->m_port, &index, &status); if (status != 0) { wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); - m_index = std::numeric_limits::max(); + m_index = std::numeric_limits::max(); m_trigger = HAL_kInvalidHandle; return; } @@ -66,7 +66,7 @@ AnalogTrigger::~AnalogTrigger() { * @param lower The lower limit of the trigger in ADC codes (12-bit values). * @param upper The upper limit of the trigger in ADC codes (12-bit values). */ -void AnalogTrigger::SetLimitsRaw(int32_t lower, int32_t upper) { +void AnalogTrigger::SetLimitsRaw(int lower, int upper) { if (StatusIsFatal()) return; int32_t status = 0; HAL_SetAnalogTriggerLimitsRaw(m_trigger, lower, upper, &status); @@ -128,7 +128,7 @@ void AnalogTrigger::SetFiltered(bool useFilteredValue) { * * @return The index of the analog trigger. */ -int32_t AnalogTrigger::GetIndex() const { +int AnalogTrigger::GetIndex() const { if (StatusIsFatal()) return -1; return m_index; } diff --git a/wpilibc/athena/src/AnalogTriggerOutput.cpp b/wpilibc/athena/src/AnalogTriggerOutput.cpp index fa49751494..8c5c7799e1 100644 --- a/wpilibc/athena/src/AnalogTriggerOutput.cpp +++ b/wpilibc/athena/src/AnalogTriggerOutput.cpp @@ -73,4 +73,4 @@ AnalogTriggerType AnalogTriggerOutput::GetAnalogTriggerTypeForRouting() const { /** * @return The channel of the source. */ -uint32_t AnalogTriggerOutput::GetChannel() const { return m_trigger.m_index; } +int AnalogTriggerOutput::GetChannel() const { return m_trigger.m_index; } diff --git a/wpilibc/athena/src/CANJaguar.cpp b/wpilibc/athena/src/CANJaguar.cpp index 0ae759bc98..cb2ce8212b 100644 --- a/wpilibc/athena/src/CANJaguar.cpp +++ b/wpilibc/athena/src/CANJaguar.cpp @@ -12,6 +12,7 @@ #include "FRC_NetworkCommunication/CANSessionMux.h" #include "HAL/HAL.h" #include "LiveWindow/LiveWindow.h" +#include "Resource.h" #include "Timer.h" #include "WPIErrors.h" @@ -27,20 +28,20 @@ #define FXP16_EQ(a, b) \ (static_cast((a)*65536.0) == static_cast((b)*65536.0)) -const int32_t CANJaguar::kControllerRate; +const int CANJaguar::kControllerRate; constexpr double CANJaguar::kApproxBusVoltage; -static const int32_t kSendMessagePeriod = 20; -static const uint32_t kFullMessageIDMask = +static const int kSendMessagePeriod = 20; +static const int kFullMessageIDMask = (CAN_MSGID_API_M | CAN_MSGID_MFR_M | CAN_MSGID_DTYPE_M); -static const int32_t kReceiveStatusAttempts = 50; +static const int kReceiveStatusAttempts = 50; static std::unique_ptr allocated; -static int32_t sendMessageHelper(uint32_t messageID, const uint8_t* data, - uint8_t dataSize, int32_t period) { - static const uint32_t kTrustedMessages[] = { +static int sendMessageHelper(int messageID, const uint8_t* data, + uint8_t dataSize, int period) { + static const int kTrustedMessages[] = { LM_API_VOLT_T_EN, LM_API_VOLT_T_SET, LM_API_SPD_T_EN, LM_API_SPD_T_SET, LM_API_VCOMP_T_EN, LM_API_VCOMP_T_SET, LM_API_POS_T_EN, LM_API_POS_T_SET, LM_API_ICTRL_T_EN, LM_API_ICTRL_T_SET}; @@ -56,7 +57,7 @@ static int32_t sendMessageHelper(uint32_t messageID, const uint8_t* data, // Make sure the data will still fit after adjusting for the token. assert(dataSize <= 6); - for (uint8_t j = 0; j < dataSize; j++) { + for (int j = 0; j < dataSize; j++) { dataBuffer[j + 2] = data[j]; } @@ -97,7 +98,7 @@ void CANJaguar::InitCANJaguar() { if (!receivedFirmwareVersion && getMessage(CAN_MSGID_API_FIRMVER, CAN_MSGID_FULL_M, dataBuffer, &dataSize)) { - m_firmwareVersion = unpackint32_t(dataBuffer); + m_firmwareVersion = unpackInt32(dataBuffer); receivedFirmwareVersion = true; } @@ -180,7 +181,7 @@ void CANJaguar::InitCANJaguar() { * @see CANJaguar#SetVoltageMode(EncoderTag, int) * @see CANJaguar#SetVoltageMode(QuadEncoderTag, int) */ -CANJaguar::CANJaguar(uint8_t deviceNumber) : m_deviceNumber(deviceNumber) { +CANJaguar::CANJaguar(int deviceNumber) : m_deviceNumber(deviceNumber) { std::stringstream buf; buf << "CANJaguar device number " << m_deviceNumber; Resource::CreateResourceObject(allocated, 63); @@ -229,7 +230,7 @@ CANJaguar::~CANJaguar() { /** * @return The CAN ID passed in the constructor */ -uint8_t CANJaguar::getDeviceNumber() const { return m_deviceNumber; } +int CANJaguar::getDeviceNumber() const { return m_deviceNumber; } /** * Sets the output set-point value. @@ -246,8 +247,8 @@ uint8_t CANJaguar::getDeviceNumber() const { return m_deviceNumber; } * @param syncGroup The update group to add this Set() to, pending * UpdateSyncGroup(). If 0, update immediately. */ -void CANJaguar::Set(float outputValue, uint8_t syncGroup) { - uint32_t messageID; +void CANJaguar::Set(float outputValue, int syncGroup) { + int messageID; uint8_t dataBuffer[8]; uint8_t dataSize; @@ -344,30 +345,30 @@ void CANJaguar::PIDWrite(float output) { } } -uint8_t CANJaguar::packPercentage(uint8_t* buffer, double value) { +int CANJaguar::packPercentage(uint8_t* buffer, double value) { int16_t intValue = static_cast(value * 32767.0); *reinterpret_cast(buffer) = swap16(intValue); return sizeof(int16_t); } -uint8_t CANJaguar::packFXP8_8(uint8_t* buffer, double value) { +int CANJaguar::packFXP8_8(uint8_t* buffer, double value) { int16_t intValue = static_cast(value * 256.0); *reinterpret_cast(buffer) = swap16(intValue); return sizeof(int16_t); } -uint8_t CANJaguar::packFXP16_16(uint8_t* buffer, double value) { - int32_t intValue = static_cast(value * 65536.0); +int CANJaguar::packFXP16_16(uint8_t* buffer, double value) { + int intValue = static_cast(value * 65536.0); *reinterpret_cast(buffer) = swap32(intValue); return sizeof(int32_t); } -uint8_t CANJaguar::packint16_t(uint8_t* buffer, int16_t value) { +int CANJaguar::packInt16(uint8_t* buffer, int16_t value) { *reinterpret_cast(buffer) = swap16(value); return sizeof(int16_t); } -uint8_t CANJaguar::packint32_t(uint8_t* buffer, int32_t value) { +int CANJaguar::packInt32(uint8_t* buffer, int32_t value) { *reinterpret_cast(buffer) = swap32(value); return sizeof(int32_t); } @@ -385,17 +386,17 @@ double CANJaguar::unpackFXP8_8(uint8_t* buffer) const { } double CANJaguar::unpackFXP16_16(uint8_t* buffer) const { - int32_t value = *reinterpret_cast(buffer); + int value = *reinterpret_cast(buffer); value = swap32(value); return value / 65536.0; } -int16_t CANJaguar::unpackint16_t(uint8_t* buffer) const { +int16_t CANJaguar::unpackInt16(uint8_t* buffer) const { int16_t value = *reinterpret_cast(buffer); return swap16(value); } -int32_t CANJaguar::unpackint32_t(uint8_t* buffer) const { +int32_t CANJaguar::unpackInt32(uint8_t* buffer) const { int32_t value = *reinterpret_cast(buffer); return swap32(value); } @@ -410,9 +411,9 @@ int32_t CANJaguar::unpackint32_t(uint8_t* buffer) const { * @param periodic If positive, tell Network Communications to send the * message every "period" milliseconds. */ -void CANJaguar::sendMessage(uint32_t messageID, const uint8_t* data, - uint8_t dataSize, int32_t period) { - int32_t localStatus = +void CANJaguar::sendMessage(int messageID, const uint8_t* data, + uint8_t dataSize, int period) { + int localStatus = sendMessageHelper(messageID | m_deviceNumber, data, dataSize, period); if (localStatus < 0) { @@ -427,7 +428,7 @@ void CANJaguar::sendMessage(uint32_t messageID, const uint8_t* data, * @param periodic If positive, tell Network Communications to send the * message every "period" milliseconds. */ -void CANJaguar::requestMessage(uint32_t messageID, int32_t period) { +void CANJaguar::requestMessage(int messageID, int period) { sendMessageHelper(messageID | m_deviceNumber, nullptr, 0, period); } @@ -444,8 +445,8 @@ void CANJaguar::requestMessage(uint32_t messageID, int32_t period) { * @return true if the message was found. Otherwise, no new message is * available. */ -bool CANJaguar::getMessage(uint32_t messageID, uint32_t messageMask, - uint8_t* data, uint8_t* dataSize) const { +bool CANJaguar::getMessage(int messageID, uint32_t messageMask, uint8_t* data, + uint8_t* dataSize) const { uint32_t targetedMessageID = messageID | m_deviceNumber; int32_t status = 0; uint32_t timeStamp; @@ -490,7 +491,7 @@ void CANJaguar::setupPeriodicStatus() { static const uint8_t kMessage2Data[] = {LM_PSTAT_LIMIT_CLR, LM_PSTAT_FAULT, LM_PSTAT_END}; - dataSize = packint16_t(data, kSendMessagePeriod); + dataSize = packInt16(data, kSendMessagePeriod); sendMessage(LM_API_PSTAT_PER_EN_S0, data, dataSize); sendMessage(LM_API_PSTAT_PER_EN_S1, data, dataSize); sendMessage(LM_API_PSTAT_PER_EN_S2, data, dataSize); @@ -638,7 +639,7 @@ void CANJaguar::verify() { if (!m_speedRefVerified) { if (getMessage(LM_API_SPD_REF, CAN_MSGID_FULL_M, dataBuffer, &dataSize)) { - uint8_t speedRef = dataBuffer[0]; + int speedRef = dataBuffer[0]; if (m_speedReference == speedRef) m_speedRefVerified = true; @@ -653,7 +654,7 @@ void CANJaguar::verify() { if (!m_posRefVerified) { if (getMessage(LM_API_POS_REF, CAN_MSGID_FULL_M, dataBuffer, &dataSize)) { - uint8_t posRef = dataBuffer[0]; + int posRef = dataBuffer[0]; if (m_positionReference == posRef) m_posRefVerified = true; @@ -667,7 +668,7 @@ void CANJaguar::verify() { } if (!m_pVerified) { - uint32_t message = 0; + int message = 0; if (m_controlMode == kSpeed) { message = LM_API_SPD_PC; @@ -697,7 +698,7 @@ void CANJaguar::verify() { } if (!m_iVerified) { - uint32_t message = 0; + int message = 0; if (m_controlMode == kSpeed) { message = LM_API_SPD_IC; @@ -727,7 +728,7 @@ void CANJaguar::verify() { } if (!m_dVerified) { - uint32_t message = 0; + int message = 0; if (m_controlMode == kSpeed) { message = LM_API_SPD_DC; @@ -775,7 +776,7 @@ void CANJaguar::verify() { if (!m_encoderCodesPerRevVerified) { if (getMessage(LM_API_CFG_ENC_LINES, CAN_MSGID_FULL_M, dataBuffer, &dataSize)) { - uint16_t codes = unpackint16_t(dataBuffer); + uint16_t codes = unpackInt16(dataBuffer); if (codes == m_encoderCodesPerRev) m_encoderCodesPerRevVerified = true; @@ -791,7 +792,7 @@ void CANJaguar::verify() { if (!m_potentiometerTurnsVerified) { if (getMessage(LM_API_CFG_POT_TURNS, CAN_MSGID_FULL_M, dataBuffer, &dataSize)) { - uint16_t turns = unpackint16_t(dataBuffer); + uint16_t turns = unpackInt16(dataBuffer); if (turns == m_potentiometerTurns) m_potentiometerTurnsVerified = true; @@ -912,7 +913,7 @@ void CANJaguar::verify() { if (!m_faultTimeVerified) { if (getMessage(LM_API_CFG_FAULT_TIME, CAN_MSGID_FULL_M, dataBuffer, &dataSize)) { - uint16_t faultTime = unpackint16_t(dataBuffer); + uint16_t faultTime = unpackInt16(dataBuffer); if (static_cast(m_faultTime * 1000.0) == faultTime) { m_faultTimeVerified = true; @@ -945,7 +946,7 @@ void CANJaguar::verify() { * * @param reference Specify a speed reference. */ -void CANJaguar::SetSpeedReference(uint8_t reference) { +void CANJaguar::SetSpeedReference(int reference) { uint8_t dataBuffer[8]; // Send the speed reference parameter @@ -962,7 +963,7 @@ void CANJaguar::SetSpeedReference(uint8_t reference) { * @return A speed reference indicating the currently selected reference device * for speed controller mode. */ -uint8_t CANJaguar::GetSpeedReference() const { return m_speedReference; } +int CANJaguar::GetSpeedReference() const { return m_speedReference; } /** * Set the reference source device for position controller mode. @@ -972,7 +973,7 @@ uint8_t CANJaguar::GetSpeedReference() const { return m_speedReference; } * * @param reference Specify a PositionReference. */ -void CANJaguar::SetPositionReference(uint8_t reference) { +void CANJaguar::SetPositionReference(int reference) { uint8_t dataBuffer[8]; // Send the position reference parameter @@ -989,7 +990,7 @@ void CANJaguar::SetPositionReference(uint8_t reference) { * @return A PositionReference indicating the currently selected reference * device for position controller mode. */ -uint8_t CANJaguar::GetPositionReference() const { return m_positionReference; } +int CANJaguar::GetPositionReference() const { return m_positionReference; } /** * Set the P, I, and D constants for the closed loop modes. @@ -1711,7 +1712,7 @@ uint16_t CANJaguar::GetFaults() const { void CANJaguar::SetVoltageRampRate(double rampRate) { uint8_t dataBuffer[8]; uint8_t dataSize; - uint32_t message; + int message; switch (m_controlMode) { case kPercentVbus: @@ -1741,14 +1742,14 @@ void CANJaguar::SetVoltageRampRate(double rampRate) { * * @return The firmware version. 0 if the device did not respond. */ -uint32_t CANJaguar::GetFirmwareVersion() const { return m_firmwareVersion; } +int CANJaguar::GetFirmwareVersion() const { return m_firmwareVersion; } /** * Get the version of the Jaguar hardware. * * @return The hardware version. 1: Jaguar, 2: Black Jaguar */ -uint8_t CANJaguar::GetHardwareVersion() const { return m_hardwareVersion; } +int CANJaguar::GetHardwareVersion() const { return m_hardwareVersion; } /** * Configure what the controller does to the H-Bridge when neutral (not driving @@ -1778,7 +1779,7 @@ void CANJaguar::ConfigEncoderCodesPerRev(uint16_t codesPerRev) { uint8_t dataBuffer[8]; // Set the codes per revolution mode - packint16_t(dataBuffer, codesPerRev); + packInt16(dataBuffer, codesPerRev); sendMessage(LM_API_CFG_ENC_LINES, dataBuffer, sizeof(uint16_t)); m_encoderCodesPerRev = codesPerRev; @@ -1798,7 +1799,7 @@ void CANJaguar::ConfigPotentiometerTurns(uint16_t turns) { uint8_t dataSize; // Set the pot turns - dataSize = packint16_t(dataBuffer, turns); + dataSize = packInt16(dataBuffer, turns); sendMessage(LM_API_CFG_POT_TURNS, dataBuffer, dataSize); m_potentiometerTurns = turns; @@ -1921,7 +1922,7 @@ void CANJaguar::ConfigFaultTime(float faultTime) { faultTime = 3.0; // Message takes ms - dataSize = packint16_t(dataBuffer, static_cast(faultTime * 1000.0)); + dataSize = packInt16(dataBuffer, static_cast(faultTime * 1000.0)); sendMessage(LM_API_CFG_FAULT_TIME, dataBuffer, dataSize); m_faultTime = faultTime; @@ -1965,7 +1966,7 @@ void CANJaguar::GetDescription(std::ostringstream& desc) const { desc << "CANJaguar ID " << m_deviceNumber; } -uint8_t CANJaguar::GetDeviceID() const { return m_deviceNumber; } +int CANJaguar::GetDeviceID() const { return m_deviceNumber; } /** * Common interface for stopping the motor until the next Set() command diff --git a/wpilibc/athena/src/CANTalon.cpp b/wpilibc/athena/src/CANTalon.cpp index a7f920b88b..7fafe719e6 100644 --- a/wpilibc/athena/src/CANTalon.cpp +++ b/wpilibc/athena/src/CANTalon.cpp @@ -31,7 +31,7 @@ const double kNativePwdUnitsPerRotation = 4096.0; */ const double kMinutesPer100msUnit = 1.0 / 600.0; -constexpr unsigned int CANTalon::kDelayForSolicitedSignalsUs; +constexpr int CANTalon::kDelayForSolicitedSignalsUs; /** * Constructor for the CANTalon device. @@ -299,7 +299,7 @@ void CANTalon::SetF(double f) { * * @see SelectProfileSlot to choose between the two sets of gains. */ -void CANTalon::SetIzone(unsigned iz) { +void CANTalon::SetIzone(int iz) { CTR_Code status = m_impl->SetIzone(m_profile, iz); if (status != CTR_OKAY) { wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); @@ -562,7 +562,7 @@ float CANTalon::GetTemperature() const { * portion of the postion based on overflows). */ void CANTalon::SetPosition(double pos) { - int32_t nativePos = ScaleRotationsToNativeUnits(m_feedbackDevice, pos); + int nativePos = ScaleRotationsToNativeUnits(m_feedbackDevice, pos); CTR_Code status = m_impl->SetSensorPosition(nativePos); if (status != CTR_OKAY) { wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); @@ -580,7 +580,7 @@ void CANTalon::SetPosition(double pos) { * When using quadrature, each unit is a quadrature edge (4X) mode. */ double CANTalon::GetPosition() const { - int32_t position; + int position; CTR_Code status = m_impl->GetSensorPosition(position); if (status != CTR_OKAY) { wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); @@ -642,7 +642,7 @@ int CANTalon::GetClosedLoopError() const { * Units: mA for Curent closed loop. * Talon Native Units for position and velocity. */ -void CANTalon::SetAllowableClosedLoopErr(uint32_t allowableCloseLoopError) { +void CANTalon::SetAllowableClosedLoopErr(int allowableCloseLoopError) { /* grab param enum */ CanTalonSRX::param_t param; if (m_profile == 1) { @@ -669,7 +669,7 @@ void CANTalon::SetAllowableClosedLoopErr(uint32_t allowableCloseLoopError) { * would then equate to 20% of a rotation per 100ms, or 10 rotations per second. */ double CANTalon::GetSpeed() const { - int32_t speed; + int speed; CTR_Code status = m_impl->GetSensorVelocity(speed); if (status != CTR_OKAY) { wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); @@ -1124,7 +1124,7 @@ void CANTalon::SetCloseLoopRampRate(double rampRate) { /** * @return The version of the firmware running on the Talon */ -uint32_t CANTalon::GetFirmwareVersion() const { +int CANTalon::GetFirmwareVersion() const { int firmwareVersion; CTR_Code status = m_impl->RequestParam(CanTalonSRX::eFirmVers); if (status != CTR_OKAY) { @@ -1378,7 +1378,7 @@ void CANTalon::ConfigLimitMode(LimitMode mode) { */ void CANTalon::ConfigForwardLimit(double forwardLimitPosition) { CTR_Code status = CTR_OKAY; - int32_t nativeLimitPos = + int nativeLimitPos = ScaleRotationsToNativeUnits(m_feedbackDevice, forwardLimitPosition); status = m_impl->SetForwardSoftLimit(nativeLimitPos); if (status != CTR_OKAY) { @@ -1459,7 +1459,7 @@ void CANTalon::ConfigRevLimitSwitchNormallyOpen(bool normallyOpen) { */ void CANTalon::ConfigReverseLimit(double reverseLimitPosition) { CTR_Code status = CTR_OKAY; - int32_t nativeLimitPos = + int nativeLimitPos = ScaleRotationsToNativeUnits(m_feedbackDevice, reverseLimitPosition); status = m_impl->SetReverseSoftLimit(nativeLimitPos); if (status != CTR_OKAY) { @@ -1514,7 +1514,7 @@ void CANTalon::ConfigNominalOutputVoltage(double forwardVoltage, * General set frame. Since the parameter is a general integral type, this can * be used for testing future features. */ -void CANTalon::ConfigSetParameter(uint32_t paramEnum, double value) { +void CANTalon::ConfigSetParameter(int paramEnum, double value) { CTR_Code status; /* config peak throttle when in closed-loop mode in the positive direction. */ status = m_impl->SetParam((CanTalonSRX::param_t)paramEnum, value); @@ -1527,7 +1527,7 @@ void CANTalon::ConfigSetParameter(uint32_t paramEnum, double value) { * General get frame. Since the parameter is a general integral type, this can * be used for testing future features. */ -bool CANTalon::GetParameter(uint32_t paramEnum, double& dvalue) const { +bool CANTalon::GetParameter(int paramEnum, double& dvalue) const { bool retval = true; /* send the request frame */ CTR_Code status = m_impl->RequestParam((CanTalonSRX::param_t)paramEnum); @@ -1658,7 +1658,7 @@ double CANTalon::GetNativeUnitsPerRotationScalar( * that the calling app does not require knowing the CPR at all. So do * both checks here. */ - int32_t qeiPulsePerCount = 4; /* default to 4x */ + int qeiPulsePerCount = 4; /* default to 4x */ switch (m_feedbackDevice) { case CtreMagEncoder_Relative: case CtreMagEncoder_Absolute: @@ -1747,14 +1747,14 @@ double CANTalon::GetNativeUnitsPerRotationScalar( * @see ConfigEncoderCodesPerRev * @return fullRotations in native engineering units of the Talon SRX firmware. */ -int32_t CANTalon::ScaleRotationsToNativeUnits(FeedbackDevice devToLookup, - double fullRotations) const { +int CANTalon::ScaleRotationsToNativeUnits(FeedbackDevice devToLookup, + double fullRotations) const { /* first assume we don't have config info, prep the default return */ - int32_t retval = static_cast(fullRotations); + int retval = static_cast(fullRotations); /* retrieve scaling info */ double scalar = GetNativeUnitsPerRotationScalar(devToLookup); /* apply scalar if its available */ - if (scalar > 0) retval = static_cast(fullRotations * scalar); + if (scalar > 0) retval = static_cast(fullRotations * scalar); return retval; } @@ -1769,15 +1769,15 @@ int32_t CANTalon::ScaleRotationsToNativeUnits(FeedbackDevice devToLookup, * @return sensor velocity in native engineering units of the Talon SRX * firmware. */ -int32_t CANTalon::ScaleVelocityToNativeUnits(FeedbackDevice devToLookup, - double rpm) const { +int CANTalon::ScaleVelocityToNativeUnits(FeedbackDevice devToLookup, + double rpm) const { /* first assume we don't have config info, prep the default return */ - int32_t retval = static_cast(rpm); + int retval = static_cast(rpm); /* retrieve scaling info */ double scalar = GetNativeUnitsPerRotationScalar(devToLookup); /* apply scalar if its available */ if (scalar > 0) { - retval = static_cast(rpm * kMinutesPer100msUnit * scalar); + retval = static_cast(rpm * kMinutesPer100msUnit * scalar); } return retval; } @@ -1793,7 +1793,7 @@ int32_t CANTalon::ScaleVelocityToNativeUnits(FeedbackDevice devToLookup, * performed. */ double CANTalon::ScaleNativeUnitsToRotations(FeedbackDevice devToLookup, - int32_t nativePos) const { + int nativePos) const { /* first assume we don't have config info, prep the default return */ double retval = static_cast(nativePos); /* retrieve scaling info */ @@ -1814,7 +1814,7 @@ double CANTalon::ScaleNativeUnitsToRotations(FeedbackDevice devToLookup, * performed. */ double CANTalon::ScaleNativeUnitsToRpm(FeedbackDevice devToLookup, - int32_t nativeVel) const { + int nativeVel) const { /* first assume we don't have config info, prep the default return */ double retval = static_cast(nativeVel); /* retrieve scaling info */ @@ -1891,15 +1891,13 @@ int CANTalon::GetMotionProfileTopLevelBufferCount() { */ bool CANTalon::PushMotionProfileTrajectory(const TrajectoryPoint& trajPt) { /* convert positiona and velocity to native units */ - int32_t targPos = - ScaleRotationsToNativeUnits(m_feedbackDevice, trajPt.position); - int32_t targVel = - ScaleVelocityToNativeUnits(m_feedbackDevice, trajPt.velocity); + int targPos = ScaleRotationsToNativeUnits(m_feedbackDevice, trajPt.position); + int targVel = ScaleVelocityToNativeUnits(m_feedbackDevice, trajPt.velocity); /* bounds check signals that require it */ - uint32_t profileSlotSelect = (trajPt.profileSlotSelect) ? 1 : 0; - uint8_t timeDurMs = (trajPt.timeDurMs >= 255) - ? 255 - : trajPt.timeDurMs; /* cap time to 255ms */ + int profileSlotSelect = (trajPt.profileSlotSelect) ? 1 : 0; + int timeDurMs = (trajPt.timeDurMs >= 255) + ? 255 + : trajPt.timeDurMs; /* cap time to 255ms */ /* send it to the top level buffer */ CTR_Code status = m_impl->PushMotionProfileTrajectory( targPos, targVel, profileSlotSelect, timeDurMs, trajPt.velocityOnly, @@ -1939,7 +1937,7 @@ void CANTalon::GetMotionProfileStatus( MotionProfileStatus& motionProfileStatus) { uint32_t flags; uint32_t profileSlotSelect; - int32_t targPos, targVel; + int targPos, targVel; uint32_t topBufferRem, topBufferCnt, btmBufferCnt; uint32_t outputEnable; /* retrieve all motion profile signals from status frame */ diff --git a/wpilibc/athena/src/CameraServer.cpp b/wpilibc/athena/src/CameraServer.cpp index 1377250bf8..4b19e8cb32 100644 --- a/wpilibc/athena/src/CameraServer.cpp +++ b/wpilibc/athena/src/CameraServer.cpp @@ -40,7 +40,7 @@ CameraServer::CameraServer() } void CameraServer::FreeImageData( - std::tuple imageData) { + std::tuple imageData) { if (std::get<3>(imageData)) { imaqDispose(std::get<0>(imageData)); } else if (std::get<0>(imageData) != nullptr) { @@ -49,8 +49,8 @@ void CameraServer::FreeImageData( } } -void CameraServer::SetImageData(uint8_t* data, unsigned int size, - unsigned int start, bool imaqData) { +void CameraServer::SetImageData(uint8_t* data, int size, int start, + bool imaqData) { std::lock_guard lock(m_imageMutex); FreeImageData(m_imageData); m_imageData = std::make_tuple(data, size, start, imaqData); @@ -58,7 +58,7 @@ void CameraServer::SetImageData(uint8_t* data, unsigned int size, } void CameraServer::SetImage(Image const* image) { - unsigned int dataSize = 0; + uint32_t dataSize = 0; uint8_t* data = reinterpret_cast( imaqFlatten(image, IMAQ_FLATTEN_IMAGE, IMAQ_COMPRESSION_JPEG, 10 * m_quality, &dataSize)); @@ -70,7 +70,7 @@ void CameraServer::SetImage(Image const* image) { std::lock_guard lock(m_imageMutex); hwClient = m_hwClient; } - unsigned int start = 0; + uint32_t start = 0; if (hwClient) { while (start < dataSize - 1) { if (data[start] == 0xFF && data[start + 1] == 0xD8) @@ -101,7 +101,7 @@ void CameraServer::AutoCapture() { } if (hwClient) { - unsigned int size = m_camera->GetImageData(data, kMaxImageSize); + int size = m_camera->GetImageData(data, kMaxImageSize); SetImageData(data, size); } else { m_camera->GetImage(frame); @@ -134,7 +134,7 @@ bool CameraServer::IsAutoCaptureStarted() { return m_autoCaptureStarted; } -void CameraServer::SetSize(unsigned int size) { +void CameraServer::SetSize(int size) { std::lock_guard lock(m_imageMutex); if (!m_camera) return; if (size == kSize160x120) @@ -145,12 +145,12 @@ void CameraServer::SetSize(unsigned int size) { m_camera->SetSize(640, 480); } -void CameraServer::SetQuality(unsigned int quality) { +void CameraServer::SetQuality(int quality) { std::lock_guard lock(m_imageMutex); m_quality = quality > 100 ? 100 : quality; } -unsigned int CameraServer::GetQuality() { +int CameraServer::GetQuality() { std::lock_guard lock(m_imageMutex); return m_quality; } @@ -238,7 +238,7 @@ void CameraServer::Serve() { auto period = std::chrono::microseconds(1000000) / req.fps; while (true) { auto startTime = std::chrono::steady_clock::now(); - std::tuple imageData; + std::tuple imageData; { std::unique_lock lock(m_imageMutex); m_newImageVariable.wait(lock); @@ -246,9 +246,9 @@ void CameraServer::Serve() { m_imageData = std::make_tuple(nullptr, 0, 0, false); } - unsigned int size = std::get<1>(imageData); - unsigned int netSize = htonl(size); - unsigned int start = std::get<2>(imageData); + int size = std::get<1>(imageData); + int netSize = htonl(size); + int start = std::get<2>(imageData); uint8_t* data = std::get<0>(imageData); if (data == nullptr) continue; diff --git a/wpilibc/athena/src/Compressor.cpp b/wpilibc/athena/src/Compressor.cpp index 52a7005089..ca7051afea 100644 --- a/wpilibc/athena/src/Compressor.cpp +++ b/wpilibc/athena/src/Compressor.cpp @@ -15,7 +15,7 @@ * * @param module The PCM ID to use (0-62) */ -Compressor::Compressor(uint8_t pcmID) : m_module(pcmID) { +Compressor::Compressor(int pcmID) : m_module(pcmID) { int32_t status = 0; m_compressorHandle = HAL_InitializeCompressor(m_module, &status); if (status != 0) { diff --git a/wpilibc/athena/src/Counter.cpp b/wpilibc/athena/src/Counter.cpp index f72c74b4e9..1165ebacc8 100644 --- a/wpilibc/athena/src/Counter.cpp +++ b/wpilibc/athena/src/Counter.cpp @@ -80,7 +80,7 @@ Counter::Counter(std::shared_ptr source) : Counter(kTwoPulse) { * @param channel The DIO channel to use as the up source. 0-9 are on-board, * 10-25 are on the MXP */ -Counter::Counter(int32_t channel) : Counter(kTwoPulse) { +Counter::Counter(int channel) : Counter(kTwoPulse) { SetUpSource(channel); ClearDownSource(); } @@ -190,7 +190,7 @@ Counter::~Counter() { * @param channel The DIO channel to use as the up source. 0-9 are on-board, * 10-25 are on the MXP */ -void Counter::SetUpSource(int32_t channel) { +void Counter::SetUpSource(int channel) { if (StatusIsFatal()) return; SetUpSource(std::make_shared(channel)); } @@ -296,7 +296,7 @@ void Counter::ClearUpSource() { * @param channel The DIO channel to use as the up source. 0-9 are on-board, * 10-25 are on the MXP */ -void Counter::SetDownSource(int32_t channel) { +void Counter::SetDownSource(int channel) { if (StatusIsFatal()) return; SetDownSource(std::make_shared(channel)); } @@ -462,7 +462,7 @@ void Counter::SetPulseLengthMode(float threshold) { */ int Counter::GetSamplesToAverage() const { int32_t status = 0; - int32_t samples = HAL_GetCounterSamplesToAverage(m_counter, &status); + int samples = HAL_GetCounterSamplesToAverage(m_counter, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); return samples; } @@ -491,10 +491,10 @@ void Counter::SetSamplesToAverage(int samplesToAverage) { * Read the value at this instant. It may still be running, so it reflects the * current value. Next time it is read, it might have a different value. */ -int32_t Counter::Get() const { +int Counter::Get() const { if (StatusIsFatal()) return 0; int32_t status = 0; - int32_t value = HAL_GetCounter(m_counter, &status); + int value = HAL_GetCounter(m_counter, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); return value; } diff --git a/wpilibc/athena/src/DigitalGlitchFilter.cpp b/wpilibc/athena/src/DigitalGlitchFilter.cpp index ba6465b081..c8889cb379 100644 --- a/wpilibc/athena/src/DigitalGlitchFilter.cpp +++ b/wpilibc/athena/src/DigitalGlitchFilter.cpp @@ -146,7 +146,7 @@ void DigitalGlitchFilter::Remove(Counter* input) { * * @param fpga_cycles The number of FPGA cycles. */ -void DigitalGlitchFilter::SetPeriodCycles(uint32_t fpga_cycles) { +void DigitalGlitchFilter::SetPeriodCycles(int fpga_cycles) { int32_t status = 0; HAL_SetFilterPeriod(m_channelIndex, fpga_cycles, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); @@ -159,7 +159,7 @@ void DigitalGlitchFilter::SetPeriodCycles(uint32_t fpga_cycles) { */ void DigitalGlitchFilter::SetPeriodNanoSeconds(uint64_t nanoseconds) { int32_t status = 0; - uint32_t fpga_cycles = + int fpga_cycles = nanoseconds * HAL_GetSystemClockTicksPerMicrosecond() / 4 / 1000; HAL_SetFilterPeriod(m_channelIndex, fpga_cycles, &status); @@ -171,9 +171,9 @@ void DigitalGlitchFilter::SetPeriodNanoSeconds(uint64_t nanoseconds) { * * @return The number of cycles. */ -uint32_t DigitalGlitchFilter::GetPeriodCycles() { +int DigitalGlitchFilter::GetPeriodCycles() { int32_t status = 0; - uint32_t fpga_cycles = HAL_GetFilterPeriod(m_channelIndex, &status); + int fpga_cycles = HAL_GetFilterPeriod(m_channelIndex, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); @@ -187,7 +187,7 @@ uint32_t DigitalGlitchFilter::GetPeriodCycles() { */ uint64_t DigitalGlitchFilter::GetPeriodNanoSeconds() { int32_t status = 0; - uint32_t fpga_cycles = HAL_GetFilterPeriod(m_channelIndex, &status); + int fpga_cycles = HAL_GetFilterPeriod(m_channelIndex, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); diff --git a/wpilibc/athena/src/DigitalInput.cpp b/wpilibc/athena/src/DigitalInput.cpp index effbf7ecbf..4a3132fafb 100644 --- a/wpilibc/athena/src/DigitalInput.cpp +++ b/wpilibc/athena/src/DigitalInput.cpp @@ -21,13 +21,13 @@ * * @param channel The DIO channel 0-9 are on-board, 10-25 are on the MXP port */ -DigitalInput::DigitalInput(uint32_t channel) { +DigitalInput::DigitalInput(int channel) { std::stringstream buf; if (!CheckDigitalChannel(channel)) { buf << "Digital Channel " << channel; wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf.str()); - m_channel = std::numeric_limits::max(); + m_channel = std::numeric_limits::max(); return; } m_channel = channel; @@ -38,7 +38,7 @@ DigitalInput::DigitalInput(uint32_t channel) { wpi_setErrorWithContextRange(status, 0, HAL_GetNumDigitalChannels(), channel, HAL_GetErrorMessage(status)); m_handle = HAL_kInvalidHandle; - m_channel = std::numeric_limits::max(); + m_channel = std::numeric_limits::max(); return; } @@ -77,7 +77,7 @@ bool DigitalInput::Get() const { /** * @return The GPIO channel number that this object represents. */ -uint32_t DigitalInput::GetChannel() const { return m_channel; } +int DigitalInput::GetChannel() const { return m_channel; } /** * @return The HAL Handle to the specified source. diff --git a/wpilibc/athena/src/DigitalOutput.cpp b/wpilibc/athena/src/DigitalOutput.cpp index ee76e717a7..188b3a80b9 100644 --- a/wpilibc/athena/src/DigitalOutput.cpp +++ b/wpilibc/athena/src/DigitalOutput.cpp @@ -21,14 +21,14 @@ * @param channel The digital channel 0-9 are on-board, 10-25 are on the MXP * port */ -DigitalOutput::DigitalOutput(uint32_t channel) { +DigitalOutput::DigitalOutput(int channel) { std::stringstream buf; m_pwmGenerator = HAL_kInvalidHandle; if (!CheckDigitalChannel(channel)) { buf << "Digital Channel " << channel; wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf.str()); - m_channel = std::numeric_limits::max(); + m_channel = std::numeric_limits::max(); return; } m_channel = channel; @@ -38,7 +38,7 @@ DigitalOutput::DigitalOutput(uint32_t channel) { if (status != 0) { wpi_setErrorWithContextRange(status, 0, HAL_GetNumDigitalChannels(), channel, HAL_GetErrorMessage(status)); - m_channel = std::numeric_limits::max(); + m_channel = std::numeric_limits::max(); m_handle = HAL_kInvalidHandle; return; } @@ -78,7 +78,7 @@ void DigitalOutput::Set(bool value) { * * @return the state of the digital output. */ -bool DigitalOutput::Get() { +bool DigitalOutput::Get() const { if (StatusIsFatal()) return false; int32_t status = 0; @@ -90,7 +90,7 @@ bool DigitalOutput::Get() { /** * @return The GPIO channel number that this object represents. */ -uint32_t DigitalOutput::GetChannel() const { return m_channel; } +int DigitalOutput::GetChannel() const { return m_channel; } /** * Output a single pulse on the digital output line. diff --git a/wpilibc/athena/src/DoubleSolenoid.cpp b/wpilibc/athena/src/DoubleSolenoid.cpp index d77a2d1d59..b2d73cc654 100644 --- a/wpilibc/athena/src/DoubleSolenoid.cpp +++ b/wpilibc/athena/src/DoubleSolenoid.cpp @@ -21,7 +21,7 @@ * @param forwardChannel The forward channel number on the PCM (0..7). * @param reverseChannel The reverse channel number on the PCM (0..7). */ -DoubleSolenoid::DoubleSolenoid(uint32_t forwardChannel, uint32_t reverseChannel) +DoubleSolenoid::DoubleSolenoid(int forwardChannel, int reverseChannel) : DoubleSolenoid(GetDefaultSolenoidModule(), forwardChannel, reverseChannel) {} @@ -32,8 +32,8 @@ DoubleSolenoid::DoubleSolenoid(uint32_t forwardChannel, uint32_t reverseChannel) * @param forwardChannel The forward channel on the PCM to control (0..7). * @param reverseChannel The reverse channel on the PCM to control (0..7). */ -DoubleSolenoid::DoubleSolenoid(uint8_t moduleNumber, uint32_t forwardChannel, - uint32_t reverseChannel) +DoubleSolenoid::DoubleSolenoid(int moduleNumber, int forwardChannel, + int reverseChannel) : SolenoidBase(moduleNumber), m_forwardChannel(forwardChannel), m_reverseChannel(reverseChannel) { @@ -120,9 +120,9 @@ void DoubleSolenoid::Set(Value value) { reverse = true; break; } - int32_t fstatus = 0; + int fstatus = 0; HAL_SetSolenoid(m_forwardHandle, forward, &fstatus); - int32_t rstatus = 0; + int rstatus = 0; HAL_SetSolenoid(m_reverseHandle, reverse, &rstatus); wpi_setErrorWithContext(fstatus, HAL_GetErrorMessage(fstatus)); @@ -136,8 +136,8 @@ void DoubleSolenoid::Set(Value value) { */ DoubleSolenoid::Value DoubleSolenoid::Get() const { if (StatusIsFatal()) return kOff; - int32_t fstatus = 0; - int32_t rstatus = 0; + int fstatus = 0; + int rstatus = 0; bool valueForward = HAL_GetSolenoid(m_forwardHandle, &fstatus); bool valueReverse = HAL_GetSolenoid(m_reverseHandle, &rstatus); diff --git a/wpilibc/athena/src/DriverStation.cpp b/wpilibc/athena/src/DriverStation.cpp index 3aad6377e7..0632d620b7 100644 --- a/wpilibc/athena/src/DriverStation.cpp +++ b/wpilibc/athena/src/DriverStation.cpp @@ -17,7 +17,7 @@ const double JOYSTICK_UNPLUGGED_MESSAGE_INTERVAL = 1.0; -const uint32_t DriverStation::kJoystickPorts; +const int DriverStation::kJoystickPorts; DriverStation::~DriverStation() { m_isRunning = false; @@ -74,7 +74,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(uint32_t stick, uint32_t axis) { +float DriverStation::GetStickAxis(int stick, int axis) { if (stick >= kJoystickPorts) { wpi_setWPIError(BadJoystickIndex); return 0; @@ -100,7 +100,7 @@ float DriverStation::GetStickAxis(uint32_t stick, uint32_t axis) { * * @return the angle of the POV in degrees, or -1 if the POV is not pressed. */ -int DriverStation::GetStickPOV(uint32_t stick, uint32_t pov) { +int DriverStation::GetStickPOV(int stick, int pov) { if (stick >= kJoystickPorts) { wpi_setWPIError(BadJoystickIndex); return -1; @@ -126,7 +126,7 @@ int DriverStation::GetStickPOV(uint32_t stick, uint32_t pov) { * @param stick The joystick to read. * @return The state of the buttons on the joystick. */ -uint32_t DriverStation::GetStickButtons(uint32_t stick) const { +int DriverStation::GetStickButtons(int stick) const { if (stick >= kJoystickPorts) { wpi_setWPIError(BadJoystickIndex); return 0; @@ -142,7 +142,7 @@ uint32_t DriverStation::GetStickButtons(uint32_t stick) const { * @param button The button index, beginning at 1. * @return The state of the joystick button. */ -bool DriverStation::GetStickButton(uint32_t stick, uint8_t button) { +bool DriverStation::GetStickButton(int stick, int button) { if (stick >= kJoystickPorts) { wpi_setWPIError(BadJoystickIndex); return false; @@ -171,7 +171,7 @@ bool DriverStation::GetStickButton(uint32_t stick, uint8_t button) { * @param stick The joystick port number * @return The number of axes on the indicated joystick */ -int DriverStation::GetStickAxisCount(uint32_t stick) const { +int DriverStation::GetStickAxisCount(int stick) const { if (stick >= kJoystickPorts) { wpi_setWPIError(BadJoystickIndex); return 0; @@ -186,7 +186,7 @@ int DriverStation::GetStickAxisCount(uint32_t stick) const { * @param stick The joystick port number * @return The number of POVs on the indicated joystick */ -int DriverStation::GetStickPOVCount(uint32_t stick) const { +int DriverStation::GetStickPOVCount(int stick) const { if (stick >= kJoystickPorts) { wpi_setWPIError(BadJoystickIndex); return 0; @@ -201,7 +201,7 @@ int DriverStation::GetStickPOVCount(uint32_t stick) const { * @param stick The joystick port number * @return The number of buttons on the indicated joystick */ -int DriverStation::GetStickButtonCount(uint32_t stick) const { +int DriverStation::GetStickButtonCount(int stick) const { if (stick >= kJoystickPorts) { wpi_setWPIError(BadJoystickIndex); return 0; @@ -216,7 +216,7 @@ int DriverStation::GetStickButtonCount(uint32_t stick) const { * @param stick The joystick port number * @return A boolean that is true if the controller is an xbox controller. */ -bool DriverStation::GetJoystickIsXbox(uint32_t stick) const { +bool DriverStation::GetJoystickIsXbox(int stick) const { if (stick >= kJoystickPorts) { wpi_setWPIError(BadJoystickIndex); return false; @@ -231,7 +231,7 @@ bool DriverStation::GetJoystickIsXbox(uint32_t stick) const { * @param stick The joystick port number * @return The HID type of joystick at the given port */ -int DriverStation::GetJoystickType(uint32_t stick) const { +int DriverStation::GetJoystickType(int stick) const { if (stick >= kJoystickPorts) { wpi_setWPIError(BadJoystickIndex); return -1; @@ -246,7 +246,7 @@ int DriverStation::GetJoystickType(uint32_t stick) const { * @param stick The joystick port number * @return The name of the joystick at the given port */ -std::string DriverStation::GetJoystickName(uint32_t stick) const { +std::string DriverStation::GetJoystickName(int stick) const { if (stick >= kJoystickPorts) { wpi_setWPIError(BadJoystickIndex); } @@ -261,7 +261,7 @@ std::string DriverStation::GetJoystickName(uint32_t stick) const { * @param stick The joystick port number and the target axis * @return What type of axis the axis is reporting to be */ -int DriverStation::GetJoystickAxisType(uint32_t stick, uint8_t axis) const { +int DriverStation::GetJoystickAxisType(int stick, int axis) const { if (stick >= kJoystickPorts) { wpi_setWPIError(BadJoystickIndex); return -1; @@ -419,7 +419,7 @@ DriverStation::Alliance DriverStation::GetAlliance() const { * * @return The location of the driver station (1-3, 0 for invalid) */ -uint32_t DriverStation::GetLocation() const { +int DriverStation::GetLocation() const { int32_t status = 0; auto allianceStationID = HAL_GetAllianceStation(&status); switch (allianceStationID) { diff --git a/wpilibc/athena/src/Encoder.cpp b/wpilibc/athena/src/Encoder.cpp index 7fe056ee18..5f6648ca81 100644 --- a/wpilibc/athena/src/Encoder.cpp +++ b/wpilibc/athena/src/Encoder.cpp @@ -68,7 +68,7 @@ void Encoder::InitEncoder(bool reverseDirection, EncodingType encodingType) { * value will either exactly match the spec'd count or * be double (2x) the spec'd count. */ -Encoder::Encoder(uint32_t aChannel, uint32_t bChannel, bool reverseDirection, +Encoder::Encoder(int aChannel, int bChannel, bool reverseDirection, EncodingType encodingType) { m_aSource = std::make_shared(aChannel); m_bSource = std::make_shared(bChannel); @@ -164,9 +164,9 @@ Encoder::~Encoder() { * * Used to divide raw edge counts down to spec'd counts. */ -int32_t Encoder::GetEncodingScale() const { +int Encoder::GetEncodingScale() const { int32_t status = 0; - int32_t val = HAL_GetEncoderEncodingScale(m_encoder, &status); + int val = HAL_GetEncoderEncodingScale(m_encoder, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); return val; } @@ -179,10 +179,10 @@ int32_t Encoder::GetEncodingScale() const { * * @return Current raw count from the encoder */ -int32_t Encoder::GetRaw() const { +int Encoder::GetRaw() const { if (StatusIsFatal()) return 0; int32_t status = 0; - int32_t value = HAL_GetEncoderRaw(m_encoder, &status); + int value = HAL_GetEncoderRaw(m_encoder, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); return value; } @@ -196,10 +196,10 @@ int32_t Encoder::GetRaw() const { * @return Current count from the Encoder adjusted for the 1x, 2x, or 4x scale * factor. */ -int32_t Encoder::Get() const { +int Encoder::Get() const { if (StatusIsFatal()) return 0; int32_t status = 0; - int32_t value = HAL_GetEncoder(m_encoder, &status); + int value = HAL_GetEncoder(m_encoder, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); return value; } @@ -445,7 +445,7 @@ double Encoder::PIDGet() { * @param channel A DIO channel to set as the encoder index * @param type The state that will cause the encoder to reset */ -void Encoder::SetIndexSource(uint32_t channel, Encoder::IndexingType type) { +void Encoder::SetIndexSource(int channel, Encoder::IndexingType type) { // Force digital input if just given an index m_indexSource = std::make_unique(channel); SetIndexSource(m_indexSource.get(), type); @@ -483,9 +483,9 @@ void Encoder::SetIndexSource(const DigitalSource& source, wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); } -int32_t Encoder::GetFPGAIndex() const { +int Encoder::GetFPGAIndex() const { int32_t status = 0; - int32_t val = HAL_GetEncoderFPGAIndex(m_encoder, &status); + int val = HAL_GetEncoderFPGAIndex(m_encoder, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); return val; } diff --git a/wpilibc/athena/src/GearTooth.cpp b/wpilibc/athena/src/GearTooth.cpp index c2c1cae7af..2406b0c7f8 100644 --- a/wpilibc/athena/src/GearTooth.cpp +++ b/wpilibc/athena/src/GearTooth.cpp @@ -27,8 +27,7 @@ void GearTooth::EnableDirectionSensing(bool directionSensitive) { * @param directionSensitive True to enable the pulse length decoding in * hardware to specify count direction. */ -GearTooth::GearTooth(uint32_t channel, bool directionSensitive) - : Counter(channel) { +GearTooth::GearTooth(int channel, bool directionSensitive) : Counter(channel) { EnableDirectionSensing(directionSensitive); LiveWindow::GetInstance()->AddSensor("GearTooth", channel, this); } diff --git a/wpilibc/athena/src/I2C.cpp b/wpilibc/athena/src/I2C.cpp index 827469e782..2e8f703bad 100644 --- a/wpilibc/athena/src/I2C.cpp +++ b/wpilibc/athena/src/I2C.cpp @@ -15,7 +15,7 @@ * @param port The I2C port to which the device is connected. * @param deviceAddress The address of the device on the I2C bus. */ -I2C::I2C(Port port, uint8_t deviceAddress) +I2C::I2C(Port port, int deviceAddress) : m_port(port), m_deviceAddress(deviceAddress) { int32_t status = 0; HAL_InitializeI2C(m_port, &status); @@ -41,8 +41,8 @@ I2C::~I2C() { HAL_CloseI2C(m_port); } * @param receiveSize Number of bytes to read from the device. * @return Transfer Aborted... false for success, true for aborted. */ -bool I2C::Transaction(uint8_t* dataToSend, uint8_t sendSize, - uint8_t* dataReceived, uint8_t receiveSize) { +bool I2C::Transaction(uint8_t* dataToSend, int sendSize, uint8_t* dataReceived, + int receiveSize) { int32_t status = 0; status = HAL_TransactionI2C(m_port, m_deviceAddress, dataToSend, sendSize, dataReceived, receiveSize); @@ -71,13 +71,13 @@ bool I2C::AddressOnly() { return Transaction(nullptr, 0, nullptr, 0); } * @param data The byte to write to the register on the device. * @return Transfer Aborted... false for success, true for aborted. */ -bool I2C::Write(uint8_t registerAddress, uint8_t data) { +bool I2C::Write(int registerAddress, uint8_t data) { uint8_t buffer[2]; buffer[0] = registerAddress; buffer[1] = data; int32_t status = 0; status = HAL_WriteI2C(m_port, m_deviceAddress, buffer, sizeof(buffer)); - return status < static_cast(sizeof(buffer)); + return status < static_cast(sizeof(buffer)); } /** @@ -90,7 +90,7 @@ bool I2C::Write(uint8_t registerAddress, uint8_t data) { * @param count The number of bytes to be written. * @return Transfer Aborted... false for success, true for aborted. */ -bool I2C::WriteBulk(uint8_t* data, uint8_t count) { +bool I2C::WriteBulk(uint8_t* data, int count) { int32_t status = 0; status = HAL_WriteI2C(m_port, m_deviceAddress, data, count); return status < count; @@ -109,7 +109,7 @@ bool I2C::WriteBulk(uint8_t* data, uint8_t count) { * read from the device. * @return Transfer Aborted... false for success, true for aborted. */ -bool I2C::Read(uint8_t registerAddress, uint8_t count, uint8_t* buffer) { +bool I2C::Read(int registerAddress, int count, uint8_t* buffer) { if (count < 1) { wpi_setWPIErrorWithContext(ParameterOutOfRange, "count"); return true; @@ -118,7 +118,8 @@ bool I2C::Read(uint8_t registerAddress, uint8_t count, uint8_t* buffer) { wpi_setWPIErrorWithContext(NullParameter, "buffer"); return true; } - return Transaction(®isterAddress, sizeof(registerAddress), buffer, count); + return Transaction(reinterpret_cast(®isterAddress), + sizeof(registerAddress), buffer, count); } /** @@ -132,7 +133,7 @@ bool I2C::Read(uint8_t registerAddress, uint8_t count, uint8_t* buffer) { * @param count The number of bytes to read in the transaction. * @return Transfer Aborted... false for success, true for aborted. */ -bool I2C::ReadOnly(uint8_t count, uint8_t* buffer) { +bool I2C::ReadOnly(int count, uint8_t* buffer) { if (count < 1) { wpi_setWPIErrorWithContext(ParameterOutOfRange, "count"); return true; @@ -155,7 +156,7 @@ bool I2C::ReadOnly(uint8_t count, uint8_t* buffer) { * @param data The value to write to the devices. */ [[gnu::warning("I2C::Broadcast() is not implemented.")]] void I2C::Broadcast( - uint8_t registerAddress, uint8_t data) {} + int registerAddress, uint8_t data) {} /** * Verify that a device's registers contain expected values. @@ -172,17 +173,17 @@ bool I2C::ReadOnly(uint8_t count, uint8_t* buffer) { * @param expected A buffer containing the values expected from the * device. */ -bool I2C::VerifySensor(uint8_t registerAddress, uint8_t count, +bool I2C::VerifySensor(int registerAddress, int count, const uint8_t* expected) { // TODO: Make use of all 7 read bytes uint8_t deviceData[4]; - for (uint8_t i = 0, curRegisterAddress = registerAddress; i < count; + for (int i = 0, curRegisterAddress = registerAddress; i < count; i += 4, curRegisterAddress += 4) { - uint8_t toRead = count - i < 4 ? count - i : 4; + int toRead = count - i < 4 ? count - i : 4; // Read the chunk of data. Return false if the sensor does not respond. if (Read(curRegisterAddress, toRead, deviceData)) return false; - for (uint8_t j = 0; j < toRead; j++) { + for (int j = 0; j < toRead; j++) { if (deviceData[j] != expected[i + j]) return false; } } diff --git a/wpilibc/athena/src/InterruptableSensorBase.cpp b/wpilibc/athena/src/InterruptableSensorBase.cpp index 487fa05349..4cf1bf15f8 100644 --- a/wpilibc/athena/src/InterruptableSensorBase.cpp +++ b/wpilibc/athena/src/InterruptableSensorBase.cpp @@ -101,7 +101,7 @@ InterruptableSensorBase::WaitResult InterruptableSensorBase::WaitForInterrupt( if (StatusIsFatal()) return InterruptableSensorBase::kTimeout; wpi_assert(m_interrupt != HAL_kInvalidHandle); int32_t status = 0; - uint32_t result; + int result; result = HAL_WaitForInterrupt(m_interrupt, timeout, ignorePrevious, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); diff --git a/wpilibc/athena/src/Jaguar.cpp b/wpilibc/athena/src/Jaguar.cpp index c75cdfc569..2f176833a2 100644 --- a/wpilibc/athena/src/Jaguar.cpp +++ b/wpilibc/athena/src/Jaguar.cpp @@ -15,7 +15,7 @@ * @param channel The PWM channel that the Jaguar is attached to. 0-9 are * on-board, 10-19 are on the MXP port */ -Jaguar::Jaguar(uint32_t channel) : PWMSpeedController(channel) { +Jaguar::Jaguar(int channel) : PWMSpeedController(channel) { /** * Input profile defined by Luminary Micro. * diff --git a/wpilibc/athena/src/Joystick.cpp b/wpilibc/athena/src/Joystick.cpp index 8b93cb7ed1..d0c57ccf08 100644 --- a/wpilibc/athena/src/Joystick.cpp +++ b/wpilibc/athena/src/Joystick.cpp @@ -11,13 +11,13 @@ #include "DriverStation.h" #include "WPIErrors.h" -const uint32_t Joystick::kDefaultXAxis; -const uint32_t Joystick::kDefaultYAxis; -const uint32_t Joystick::kDefaultZAxis; -const uint32_t Joystick::kDefaultTwistAxis; -const uint32_t Joystick::kDefaultThrottleAxis; -const uint32_t Joystick::kDefaultTriggerButton; -const uint32_t Joystick::kDefaultTopButton; +const int Joystick::kDefaultXAxis; +const int Joystick::kDefaultYAxis; +const int Joystick::kDefaultZAxis; +const int Joystick::kDefaultTwistAxis; +const int Joystick::kDefaultThrottleAxis; +const int Joystick::kDefaultTriggerButton; +const int Joystick::kDefaultTopButton; static Joystick* joysticks[DriverStation::kJoystickPorts]; static bool joySticksInitialized = false; @@ -29,8 +29,7 @@ static bool joySticksInitialized = false; * @param port The port on the driver station that the joystick is plugged into * (0-5). */ -Joystick::Joystick(uint32_t port) - : Joystick(port, kNumAxisTypes, kNumButtonTypes) { +Joystick::Joystick(int port) : Joystick(port, kNumAxisTypes, kNumButtonTypes) { m_axes[kXAxis] = kDefaultXAxis; m_axes[kYAxis] = kDefaultYAxis; m_axes[kZAxis] = kDefaultZAxis; @@ -54,8 +53,7 @@ Joystick::Joystick(uint32_t port) * @param numAxisTypes The number of axis types in the enum. * @param numButtonTypes The number of button types in the enum. */ -Joystick::Joystick(uint32_t port, uint32_t numAxisTypes, - uint32_t numButtonTypes) +Joystick::Joystick(int port, int numAxisTypes, int numButtonTypes) : m_ds(DriverStation::GetInstance()), m_port(port), m_axes(numAxisTypes), @@ -71,7 +69,7 @@ Joystick::Joystick(uint32_t port, uint32_t numAxisTypes, } } -Joystick* Joystick::GetStickForPort(uint32_t port) { +Joystick* Joystick::GetStickForPort(int port) { Joystick* stick = joysticks[port]; if (stick == nullptr) { stick = new Joystick(port); @@ -133,7 +131,7 @@ float Joystick::GetThrottle() const { * @param axis The axis to read, starting at 0. * @return The value of the axis. */ -float Joystick::GetRawAxis(uint32_t axis) const { +float Joystick::GetRawAxis(int axis) const { return m_ds.GetStickAxis(m_port, axis); } @@ -211,7 +209,7 @@ bool Joystick::GetBumper(JoystickHand hand) const { * @param button The button number to be read (starting at 1) * @return The state of the button. **/ -bool Joystick::GetRawButton(uint32_t button) const { +bool Joystick::GetRawButton(int button) const { return m_ds.GetStickButton(m_port, button); } @@ -224,9 +222,7 @@ bool Joystick::GetRawButton(uint32_t button) const { * @param pov The index of the POV to read (starting at 0) * @return the angle of the POV in degrees, or -1 if the POV is not pressed. */ -int Joystick::GetPOV(uint32_t pov) const { - return m_ds.GetStickPOV(m_port, pov); -} +int Joystick::GetPOV(int pov) const { return m_ds.GetStickPOV(m_port, pov); } /** * Get buttons based on an enumerated type. @@ -315,7 +311,7 @@ int Joystick::GetPOVCount() const { return m_ds.GetStickPOVCount(m_port); } * @param axis The axis to look up the channel for. * @return The channel fr the axis. */ -uint32_t Joystick::GetAxisChannel(AxisType axis) const { return m_axes[axis]; } +int Joystick::GetAxisChannel(AxisType axis) const { return m_axes[axis]; } /** * Set the channel associated with a specified axis. @@ -323,7 +319,7 @@ uint32_t Joystick::GetAxisChannel(AxisType axis) const { return m_axes[axis]; } * @param axis The axis to set the channel for. * @param channel The channel to set the axis to. */ -void Joystick::SetAxisChannel(AxisType axis, uint32_t channel) { +void Joystick::SetAxisChannel(AxisType axis, int channel) { m_axes[axis] = channel; } @@ -385,7 +381,7 @@ void Joystick::SetRumble(RumbleType type, float value) { * @param value The value to set the output to */ -void Joystick::SetOutput(uint8_t outputNumber, bool value) { +void Joystick::SetOutput(int outputNumber, bool value) { m_outputs = (m_outputs & ~(1 << (outputNumber - 1))) | (value << (outputNumber - 1)); @@ -397,7 +393,7 @@ void Joystick::SetOutput(uint8_t outputNumber, bool value) { * * @param value The 32 bit output value (1 bit for each output) */ -void Joystick::SetOutputs(uint32_t value) { +void Joystick::SetOutputs(int value) { m_outputs = value; HAL_SetJoystickOutputs(m_port, m_outputs, m_leftRumble, m_rightRumble); } diff --git a/wpilibc/athena/src/PIDController.cpp b/wpilibc/athena/src/PIDController.cpp index dcb6240959..5d2f3e2dd6 100644 --- a/wpilibc/athena/src/PIDController.cpp +++ b/wpilibc/athena/src/PIDController.cpp @@ -67,7 +67,7 @@ PIDController::PIDController(float Kp, float Ki, float Kd, float Kf, m_controlLoop->StartPeriodic(m_period); m_setpointTimer.Start(); - static int32_t instances = 0; + static int instances = 0; instances++; HAL_Report(HALUsageReporting::kResourceType_PIDController, instances); } @@ -473,12 +473,12 @@ void PIDController::SetPercentTolerance(float percent) { * * @param bufLength Number of previous cycles to average. Defaults to 1. */ -void PIDController::SetToleranceBuffer(unsigned bufLength) { +void PIDController::SetToleranceBuffer(int bufLength) { std::lock_guard sync(m_mutex); m_bufLength = bufLength; // Cut the buffer down to size if needed. - while (m_buf.size() > bufLength) { + while (m_buf.size() > static_cast(bufLength)) { m_bufTotal -= m_buf.front(); m_buf.pop(); } diff --git a/wpilibc/athena/src/PWM.cpp b/wpilibc/athena/src/PWM.cpp index abadcb4118..6d7875444e 100644 --- a/wpilibc/athena/src/PWM.cpp +++ b/wpilibc/athena/src/PWM.cpp @@ -23,7 +23,7 @@ * @param channel The PWM channel number. 0-9 are on-board, 10-19 are on the * MXP port */ -PWM::PWM(uint32_t channel) { +PWM::PWM(int channel) { std::stringstream buf; if (!CheckPWMChannel(channel)) { @@ -37,7 +37,7 @@ PWM::PWM(uint32_t channel) { if (status != 0) { wpi_setErrorWithContextRange(status, 0, HAL_GetNumPWMChannels(), channel, HAL_GetErrorMessage(status)); - m_channel = std::numeric_limits::max(); + m_channel = std::numeric_limits::max(); m_handle = HAL_kInvalidHandle; return; } @@ -120,8 +120,8 @@ void PWM::SetBounds(float max, float deadbandMax, float center, * @param deadbandMin The low end of the deadband range * @param min The minimum pwm value */ -void PWM::SetRawBounds(int32_t max, int32_t deadbandMax, int32_t center, - int32_t deadbandMin, int32_t min) { +void PWM::SetRawBounds(int max, int deadbandMax, int center, int deadbandMin, + int min) { if (StatusIsFatal()) return; int32_t status = 0; HAL_SetPWMConfigRaw(m_handle, max, deadbandMax, center, deadbandMin, min, @@ -142,8 +142,8 @@ void PWM::SetRawBounds(int32_t max, int32_t deadbandMax, int32_t center, * @param deadbandMin The low end of the deadband range * @param min The minimum pwm value */ -void PWM::GetRawBounds(int32_t* max, int32_t* deadbandMax, int32_t* center, - int32_t* deadbandMin, int32_t* min) { +void PWM::GetRawBounds(int* max, int* deadbandMax, int* center, + int* deadbandMin, int* min) { int32_t status = 0; HAL_GetPWMConfigRaw(m_handle, max, deadbandMax, center, deadbandMin, min, &status); diff --git a/wpilibc/athena/src/PWMSpeedController.cpp b/wpilibc/athena/src/PWMSpeedController.cpp index 87d1c91ccf..fdc2f15a71 100644 --- a/wpilibc/athena/src/PWMSpeedController.cpp +++ b/wpilibc/athena/src/PWMSpeedController.cpp @@ -13,7 +13,7 @@ * @param channel The PWM channel that the controller is attached to. 0-9 are * on-board, 10-19 are on the MXP port */ -PWMSpeedController::PWMSpeedController(uint32_t channel) : SafePWM(channel) {} +PWMSpeedController::PWMSpeedController(int channel) : SafePWM(channel) {} /** * Set the PWM value. diff --git a/wpilibc/athena/src/PowerDistributionPanel.cpp b/wpilibc/athena/src/PowerDistributionPanel.cpp index 56f51d307a..757e466197 100644 --- a/wpilibc/athena/src/PowerDistributionPanel.cpp +++ b/wpilibc/athena/src/PowerDistributionPanel.cpp @@ -18,8 +18,7 @@ PowerDistributionPanel::PowerDistributionPanel() : PowerDistributionPanel(0) {} /** * Initialize the PDP. */ -PowerDistributionPanel::PowerDistributionPanel(uint8_t module) - : m_module(module) { +PowerDistributionPanel::PowerDistributionPanel(int module) : m_module(module) { int32_t status = 0; HAL_InitializePDP(m_module, &status); if (status != 0) { @@ -71,7 +70,7 @@ float PowerDistributionPanel::GetTemperature() const { * * @return The current of one of the PDP channels (channels 0-15) in Amperes */ -float PowerDistributionPanel::GetCurrent(uint8_t channel) const { +float PowerDistributionPanel::GetCurrent(int channel) const { if (StatusIsFatal()) return 0; int32_t status = 0; diff --git a/wpilibc/athena/src/Preferences.cpp b/wpilibc/athena/src/Preferences.cpp index 8b0881d536..7b506e76ab 100644 --- a/wpilibc/athena/src/Preferences.cpp +++ b/wpilibc/athena/src/Preferences.cpp @@ -20,7 +20,7 @@ void Preferences::Listener::ValueChanged(ITable* source, llvm::StringRef key, bool isNew) {} void Preferences::Listener::ValueChangedEx(ITable* source, llvm::StringRef key, std::shared_ptr value, - unsigned int flags) { + uint32_t flags) { source->SetPersistent(key); } diff --git a/wpilibc/athena/src/Relay.cpp b/wpilibc/athena/src/Relay.cpp index 0e3f9acd98..c4e0af6ddd 100644 --- a/wpilibc/athena/src/Relay.cpp +++ b/wpilibc/athena/src/Relay.cpp @@ -23,7 +23,7 @@ * @param channel The channel number (0-3). * @param direction The direction that the Relay object will control. */ -Relay::Relay(uint32_t channel, Relay::Direction direction) +Relay::Relay(int channel, Relay::Direction direction) : m_channel(channel), m_direction(direction) { std::stringstream buf; if (!SensorBase::CheckRelayChannel(m_channel)) { @@ -206,7 +206,7 @@ Relay::Value Relay::Get() const { wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); } -uint32_t Relay::GetChannel() const { return m_channel; } +int Relay::GetChannel() const { return m_channel; } /** * Set the expiration time for the Relay object diff --git a/wpilibc/athena/src/RobotDrive.cpp b/wpilibc/athena/src/RobotDrive.cpp index 42dc715203..01392154cc 100644 --- a/wpilibc/athena/src/RobotDrive.cpp +++ b/wpilibc/athena/src/RobotDrive.cpp @@ -17,7 +17,7 @@ #include "Utility.h" #include "WPIErrors.h" -const int32_t RobotDrive::kMaxNumberOfMotors; +const int RobotDrive::kMaxNumberOfMotors; static auto make_shared_nodelete(SpeedController* ptr) { return std::shared_ptr(ptr, NullDeleter()); @@ -55,7 +55,7 @@ void RobotDrive::InitRobotDrive() { * @param rightMotorChannel The PWM channel number that drives the right motor. * 0-9 are on-board, 10-19 are on the MXP port */ -RobotDrive::RobotDrive(uint32_t leftMotorChannel, uint32_t rightMotorChannel) { +RobotDrive::RobotDrive(int leftMotorChannel, int rightMotorChannel) { InitRobotDrive(); m_rearLeftMotor = std::make_shared(leftMotorChannel); m_rearRightMotor = std::make_shared(rightMotorChannel); @@ -78,8 +78,8 @@ RobotDrive::RobotDrive(uint32_t leftMotorChannel, uint32_t rightMotorChannel) { * @param rearRightMotor Rear Right motor channel number. 0-9 are on-board, * 10-19 are on the MXP port */ -RobotDrive::RobotDrive(uint32_t frontLeftMotor, uint32_t rearLeftMotor, - uint32_t frontRightMotor, uint32_t rearRightMotor) { +RobotDrive::RobotDrive(int frontLeftMotor, int rearLeftMotor, + int frontRightMotor, int rearRightMotor) { InitRobotDrive(); m_rearLeftMotor = std::make_shared(rearLeftMotor); m_rearRightMotor = std::make_shared(rearRightMotor); @@ -275,8 +275,8 @@ void RobotDrive::TankDrive(GenericHID& leftStick, GenericHID& rightStick, * robot. * @param rightAxis The axis to select on the right side Joystick object. */ -void RobotDrive::TankDrive(GenericHID* leftStick, uint32_t leftAxis, - GenericHID* rightStick, uint32_t rightAxis, +void RobotDrive::TankDrive(GenericHID* leftStick, int leftAxis, + GenericHID* rightStick, int rightAxis, bool squaredInputs) { if (leftStick == nullptr || rightStick == nullptr) { wpi_setWPIError(NullParameter); @@ -286,8 +286,8 @@ void RobotDrive::TankDrive(GenericHID* leftStick, uint32_t leftAxis, squaredInputs); } -void RobotDrive::TankDrive(GenericHID& leftStick, uint32_t leftAxis, - GenericHID& rightStick, uint32_t rightAxis, +void RobotDrive::TankDrive(GenericHID& leftStick, int leftAxis, + GenericHID& rightStick, int rightAxis, bool squaredInputs) { TankDrive(leftStick.GetRawAxis(leftAxis), rightStick.GetRawAxis(rightAxis), squaredInputs); @@ -382,8 +382,8 @@ void RobotDrive::ArcadeDrive(GenericHID& stick, bool squaredInputs) { * @param squaredInputs Setting this parameter to true increases the * sensitivity at lower speeds */ -void RobotDrive::ArcadeDrive(GenericHID* moveStick, uint32_t moveAxis, - GenericHID* rotateStick, uint32_t rotateAxis, +void RobotDrive::ArcadeDrive(GenericHID* moveStick, int moveAxis, + GenericHID* rotateStick, int rotateAxis, bool squaredInputs) { float moveValue = moveStick->GetRawAxis(moveAxis); float rotateValue = rotateStick->GetRawAxis(rotateAxis); @@ -407,8 +407,8 @@ void RobotDrive::ArcadeDrive(GenericHID* moveStick, uint32_t moveAxis, * @param squaredInputs Setting this parameter to true increases the * sensitivity at lower speeds */ -void RobotDrive::ArcadeDrive(GenericHID& moveStick, uint32_t moveAxis, - GenericHID& rotateStick, uint32_t rotateAxis, +void RobotDrive::ArcadeDrive(GenericHID& moveStick, int moveAxis, + GenericHID& rotateStick, int rotateAxis, bool squaredInputs) { float moveValue = moveStick.GetRawAxis(moveAxis); float rotateValue = rotateStick.GetRawAxis(rotateAxis); @@ -637,7 +637,7 @@ float RobotDrive::Limit(float num) { */ void RobotDrive::Normalize(double* wheelSpeeds) { double maxMagnitude = std::fabs(wheelSpeeds[0]); - int32_t i; + int i; for (i = 1; i < kMaxNumberOfMotors; i++) { double temp = std::fabs(wheelSpeeds[i]); if (maxMagnitude < temp) maxMagnitude = temp; diff --git a/wpilibc/athena/src/SD540.cpp b/wpilibc/athena/src/SD540.cpp index de409c18bc..c5a87ff3c7 100644 --- a/wpilibc/athena/src/SD540.cpp +++ b/wpilibc/athena/src/SD540.cpp @@ -31,7 +31,7 @@ * @param channel The PWM channel that the SD540 is attached to. 0-9 are * on-board, 10-19 are on the MXP port */ -SD540::SD540(uint32_t channel) : PWMSpeedController(channel) { +SD540::SD540(int channel) : PWMSpeedController(channel) { SetBounds(2.05, 1.55, 1.50, 1.44, .94); SetPeriodMultiplier(kPeriodMultiplier_1X); SetSpeed(0.0); diff --git a/wpilibc/athena/src/SPI.cpp b/wpilibc/athena/src/SPI.cpp index 6bd9bcbdf0..9367d627b8 100644 --- a/wpilibc/athena/src/SPI.cpp +++ b/wpilibc/athena/src/SPI.cpp @@ -23,7 +23,7 @@ SPI::SPI(Port SPIport) { HAL_InitializeSPI(m_port, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); - static int32_t instances = 0; + static int instances = 0; instances++; HAL_Report(HALUsageReporting::kResourceType_SPI, instances); } @@ -122,8 +122,8 @@ void SPI::SetChipSelectActiveLow() { * If not running in output only mode, also saves the data received * on the MISO input during the transfer into the receive FIFO. */ -int32_t SPI::Write(uint8_t* data, uint8_t size) { - int32_t retVal = 0; +int SPI::Write(uint8_t* data, int size) { + int retVal = 0; retVal = HAL_WriteSPI(m_port, data, size); return retVal; } @@ -141,8 +141,8 @@ int32_t SPI::Write(uint8_t* data, uint8_t size) { * that data is already in the receive FIFO from a previous * write. */ -int32_t SPI::Read(bool initiate, uint8_t* dataReceived, uint8_t size) { - int32_t retVal = 0; +int SPI::Read(bool initiate, uint8_t* dataReceived, int size) { + int retVal = 0; if (initiate) { auto dataToSend = new uint8_t[size]; std::memset(dataToSend, 0, size); @@ -160,9 +160,8 @@ int32_t SPI::Read(bool initiate, uint8_t* dataReceived, uint8_t size) { * @param dataReceived Buffer to receive data from the device * @param size The length of the transaction, in bytes */ -int32_t SPI::Transaction(uint8_t* dataToSend, uint8_t* dataReceived, - uint8_t size) { - int32_t retVal = 0; +int SPI::Transaction(uint8_t* dataToSend, uint8_t* dataReceived, int size) { + int retVal = 0; retVal = HAL_TransactionSPI(m_port, dataToSend, dataReceived, size); return retVal; } @@ -182,12 +181,11 @@ int32_t SPI::Transaction(uint8_t* dataToSend, uint8_t* dataReceived, * @param is_signed Is data field signed? * @param big_endian Is device big endian? */ -void SPI::InitAccumulator(double period, uint32_t cmd, uint8_t xfer_size, - uint32_t valid_mask, uint32_t valid_value, - uint8_t data_shift, uint8_t data_size, bool is_signed, - bool big_endian) { +void SPI::InitAccumulator(double period, int cmd, int xfer_size, int valid_mask, + int valid_value, int data_shift, int data_size, + bool is_signed, bool big_endian) { int32_t status = 0; - HAL_InitSPIAccumulator(m_port, static_cast(period * 1e6), cmd, + HAL_InitSPIAccumulator(m_port, static_cast(period * 1e6), cmd, xfer_size, valid_mask, valid_value, data_shift, data_size, is_signed, big_endian, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); @@ -219,7 +217,7 @@ void SPI::ResetAccumulator() { * accelerometers to make integration work and to take the device offset into * account when integrating. */ -void SPI::SetAccumulatorCenter(int32_t center) { +void SPI::SetAccumulatorCenter(int center) { int32_t status = 0; HAL_SetSPIAccumulatorCenter(m_port, center, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); @@ -228,7 +226,7 @@ void SPI::SetAccumulatorCenter(int32_t center) { /** * Set the accumulator's deadband. */ -void SPI::SetAccumulatorDeadband(int32_t deadband) { +void SPI::SetAccumulatorDeadband(int deadband) { int32_t status = 0; HAL_SetSPIAccumulatorDeadband(m_port, deadband, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); @@ -237,9 +235,9 @@ void SPI::SetAccumulatorDeadband(int32_t deadband) { /** * Read the last value read by the accumulator engine. */ -int32_t SPI::GetAccumulatorLastValue() const { +int SPI::GetAccumulatorLastValue() const { int32_t status = 0; - int32_t retVal = HAL_GetSPIAccumulatorLastValue(m_port, &status); + int retVal = HAL_GetSPIAccumulatorLastValue(m_port, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); return retVal; } diff --git a/wpilibc/athena/src/SafePWM.cpp b/wpilibc/athena/src/SafePWM.cpp index 0ba2c85718..abf1d50c32 100644 --- a/wpilibc/athena/src/SafePWM.cpp +++ b/wpilibc/athena/src/SafePWM.cpp @@ -13,7 +13,7 @@ * @param channel The PWM channel number 0-9 are on-board, 10-19 are on the MXP * port */ -SafePWM::SafePWM(uint32_t channel) : PWM(channel) { +SafePWM::SafePWM(int channel) : PWM(channel) { m_safetyHelper = std::make_unique(this); m_safetyHelper->SetSafetyEnabled(false); } diff --git a/wpilibc/athena/src/SerialPort.cpp b/wpilibc/athena/src/SerialPort.cpp index 007623ee6c..60667a90f5 100644 --- a/wpilibc/athena/src/SerialPort.cpp +++ b/wpilibc/athena/src/SerialPort.cpp @@ -23,7 +23,7 @@ * @param stopBits The number of stop bits to use as defined by the enum * StopBits. */ -SerialPort::SerialPort(uint32_t baudRate, Port port, uint8_t dataBits, +SerialPort::SerialPort(int baudRate, Port port, int dataBits, SerialPort::Parity parity, SerialPort::StopBits stopBits) { int32_t status = 0; @@ -105,9 +105,9 @@ void SerialPort::DisableTermination() { * * @return The number of bytes available to read */ -int32_t SerialPort::GetBytesReceived() { +int SerialPort::GetBytesReceived() { int32_t status = 0; - int32_t retVal = HAL_GetSerialBytesReceived(m_port, &status); + int retVal = HAL_GetSerialBytesReceived(m_port, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); return retVal; } @@ -119,9 +119,9 @@ int32_t SerialPort::GetBytesReceived() { * @param count The maximum number of bytes to read. * @return The number of bytes actually read into the buffer. */ -uint32_t SerialPort::Read(char* buffer, int32_t count) { +int SerialPort::Read(char* buffer, int count) { int32_t status = 0; - int32_t retVal = HAL_ReadSerial(m_port, buffer, count, &status); + int retVal = HAL_ReadSerial(m_port, buffer, count, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); return retVal; } @@ -133,9 +133,9 @@ uint32_t SerialPort::Read(char* buffer, int32_t count) { * @param count The maximum number of bytes to write. * @return The number of bytes actually written into the port. */ -uint32_t SerialPort::Write(const std::string& buffer, int32_t count) { +int SerialPort::Write(const std::string& buffer, int count) { int32_t status = 0; - int32_t retVal = HAL_WriteSerial(m_port, buffer.c_str(), count, &status); + int retVal = HAL_WriteSerial(m_port, buffer.c_str(), count, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); return retVal; } @@ -166,7 +166,7 @@ void SerialPort::SetTimeout(float timeout) { * * @param size The read buffer size. */ -void SerialPort::SetReadBufferSize(uint32_t size) { +void SerialPort::SetReadBufferSize(int size) { int32_t status = 0; HAL_SetSerialReadBufferSize(m_port, size, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); @@ -180,7 +180,7 @@ void SerialPort::SetReadBufferSize(uint32_t size) { * * @param size The write buffer size. */ -void SerialPort::SetWriteBufferSize(uint32_t size) { +void SerialPort::SetWriteBufferSize(int size) { int32_t status = 0; HAL_SetSerialWriteBufferSize(m_port, size, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); diff --git a/wpilibc/athena/src/Servo.cpp b/wpilibc/athena/src/Servo.cpp index 68f99ff89f..96f04956d6 100644 --- a/wpilibc/athena/src/Servo.cpp +++ b/wpilibc/athena/src/Servo.cpp @@ -19,7 +19,7 @@ constexpr float Servo::kDefaultMinServoPWM; * @param channel The PWM channel to which the servo is attached. 0-9 are * on-board, 10-19 are on the MXP port */ -Servo::Servo(uint32_t channel) : SafePWM(channel) { +Servo::Servo(int channel) : SafePWM(channel) { // Set minimum and maximum PWM values supported by the servo SetBounds(kDefaultMaxServoPWM, 0.0, 0.0, 0.0, kDefaultMinServoPWM); diff --git a/wpilibc/athena/src/Solenoid.cpp b/wpilibc/athena/src/Solenoid.cpp index 083ff3e6ab..1285dad94b 100644 --- a/wpilibc/athena/src/Solenoid.cpp +++ b/wpilibc/athena/src/Solenoid.cpp @@ -18,7 +18,7 @@ * * @param channel The channel on the PCM to control (0..7). */ -Solenoid::Solenoid(uint32_t channel) +Solenoid::Solenoid(int channel) : Solenoid(GetDefaultSolenoidModule(), channel) {} /** @@ -27,7 +27,7 @@ Solenoid::Solenoid(uint32_t channel) * @param moduleNumber The CAN ID of the PCM the solenoid is attached to * @param channel The channel on the PCM to control (0..7). */ -Solenoid::Solenoid(uint8_t moduleNumber, uint32_t channel) +Solenoid::Solenoid(int moduleNumber, int channel) : SolenoidBase(moduleNumber), m_channel(channel) { std::stringstream buf; if (!CheckSolenoidModule(m_moduleNumber)) { diff --git a/wpilibc/athena/src/SolenoidBase.cpp b/wpilibc/athena/src/SolenoidBase.cpp index 05631f907b..a4ec97fe1c 100644 --- a/wpilibc/athena/src/SolenoidBase.cpp +++ b/wpilibc/athena/src/SolenoidBase.cpp @@ -14,18 +14,17 @@ * * @param moduleNumber The CAN PCM ID. */ -SolenoidBase::SolenoidBase(uint8_t moduleNumber) - : m_moduleNumber(moduleNumber) {} +SolenoidBase::SolenoidBase(int moduleNumber) : m_moduleNumber(moduleNumber) {} /** * Read all 8 solenoids as a single byte * * @return The current value of all 8 solenoids on the module. */ -uint8_t SolenoidBase::GetAll(int module) const { - uint8_t value = 0; +int SolenoidBase::GetAll(int module) const { + int value = 0; int32_t status = 0; - value = HAL_GetAllSolenoids(static_cast(module), &status); + value = HAL_GetAllSolenoids(static_cast(module), &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); return value; } @@ -39,9 +38,9 @@ uint8_t SolenoidBase::GetAll(int module) const { * * @return The solenoid blacklist of all 8 solenoids on the module. */ -uint8_t SolenoidBase::GetPCMSolenoidBlackList(int module) const { +int SolenoidBase::GetPCMSolenoidBlackList(int module) const { int32_t status = 0; - return HAL_GetPCMSolenoidBlackList(static_cast(module), &status); + return HAL_GetPCMSolenoidBlackList(static_cast(module), &status); } /** @@ -50,7 +49,7 @@ uint8_t SolenoidBase::GetPCMSolenoidBlackList(int module) const { */ bool SolenoidBase::GetPCMSolenoidVoltageStickyFault(int module) const { int32_t status = 0; - return HAL_GetPCMSolenoidVoltageStickyFault(static_cast(module), + return HAL_GetPCMSolenoidVoltageStickyFault(static_cast(module), &status); } @@ -60,7 +59,7 @@ bool SolenoidBase::GetPCMSolenoidVoltageStickyFault(int module) const { */ bool SolenoidBase::GetPCMSolenoidVoltageFault(int module) const { int32_t status = 0; - return HAL_GetPCMSolenoidVoltageFault(static_cast(module), &status); + return HAL_GetPCMSolenoidVoltageFault(static_cast(module), &status); } /** @@ -75,5 +74,5 @@ bool SolenoidBase::GetPCMSolenoidVoltageFault(int module) const { */ void SolenoidBase::ClearAllPCMStickyFaults(int module) { int32_t status = 0; - return HAL_ClearAllPCMStickyFaults(static_cast(module), &status); + return HAL_ClearAllPCMStickyFaults(static_cast(module), &status); } diff --git a/wpilibc/athena/src/Spark.cpp b/wpilibc/athena/src/Spark.cpp index eaa81fd7d8..75d15e0a52 100644 --- a/wpilibc/athena/src/Spark.cpp +++ b/wpilibc/athena/src/Spark.cpp @@ -31,7 +31,7 @@ * @param channel The PWM channel that the Spark is attached to. 0-9 are * on-board, 10-19 are on the MXP port */ -Spark::Spark(uint32_t channel) : PWMSpeedController(channel) { +Spark::Spark(int channel) : PWMSpeedController(channel) { SetBounds(2.003, 1.55, 1.50, 1.46, .999); SetPeriodMultiplier(kPeriodMultiplier_1X); SetSpeed(0.0); diff --git a/wpilibc/athena/src/Talon.cpp b/wpilibc/athena/src/Talon.cpp index afc3d3918a..23c9ac67ab 100644 --- a/wpilibc/athena/src/Talon.cpp +++ b/wpilibc/athena/src/Talon.cpp @@ -16,7 +16,7 @@ * @param channel The PWM channel number that the Talon is attached to. 0-9 are * on-board, 10-19 are on the MXP port */ -Talon::Talon(uint32_t channel) : PWMSpeedController(channel) { +Talon::Talon(int channel) : PWMSpeedController(channel) { /* Note that the Talon uses the following bounds for PWM values. These values * should work reasonably well for most controllers, but if users experience * issues such as asymmetric behavior around the deadband or inability to diff --git a/wpilibc/athena/src/TalonSRX.cpp b/wpilibc/athena/src/TalonSRX.cpp index d0370f6db3..dd8ce722bf 100644 --- a/wpilibc/athena/src/TalonSRX.cpp +++ b/wpilibc/athena/src/TalonSRX.cpp @@ -16,7 +16,7 @@ * @param channel The PWM channel that the TalonSRX is attached to. 0-9 are * on-board, 10-19 are on the MXP port */ -TalonSRX::TalonSRX(uint32_t channel) : PWMSpeedController(channel) { +TalonSRX::TalonSRX(int channel) : PWMSpeedController(channel) { /* Note that the TalonSRX uses the following bounds for PWM values. These * values should work reasonably well for most controllers, but if users * experience issues such as asymmetric behavior around the deadband or diff --git a/wpilibc/athena/src/Task.cpp b/wpilibc/athena/src/Task.cpp index 84f01ec094..82cbf36285 100644 --- a/wpilibc/athena/src/Task.cpp +++ b/wpilibc/athena/src/Task.cpp @@ -18,7 +18,7 @@ #define ERROR (-1) #endif /* ERROR */ -const uint32_t Task::kDefaultPriority; +const int Task::kDefaultPriority; Task& Task::operator=(Task&& task) { m_thread.swap(task.m_thread); @@ -60,7 +60,7 @@ bool Task::Verify() { * * @return task priority or 0 if an error occured */ -int32_t Task::GetPriority() { +int Task::GetPriority() { int priority; auto id = m_thread.native_handle(); if (HandleError(HAL_GetTaskPriority(&id, &priority))) @@ -77,7 +77,7 @@ int32_t Task::GetPriority() { * @param priority The priority at which the internal thread should run. * @return true on success. */ -bool Task::SetPriority(int32_t priority) { +bool Task::SetPriority(int priority) { auto id = m_thread.native_handle(); return HandleError(HAL_SetTaskPriority(&id, priority)); } diff --git a/wpilibc/athena/src/USBCamera.cpp b/wpilibc/athena/src/USBCamera.cpp index 0fa8cca9fd..a9cd5d9d7c 100644 --- a/wpilibc/athena/src/USBCamera.cpp +++ b/wpilibc/athena/src/USBCamera.cpp @@ -22,7 +22,7 @@ // To call it, just give the name of the function and the arguments #define SAFE_IMAQ_CALL(funName, ...) \ { \ - unsigned int error = funName(__VA_ARGS__); \ + int error = funName(__VA_ARGS__); \ if (error != IMAQdxErrorSuccess) \ wpi_setImaqErrorWithContext(error, #funName); \ } @@ -33,15 +33,15 @@ * http://stackoverflow.com/a/1602428. Be sure to also read the comments for * the SOS flag explanation. */ -unsigned int USBCamera::GetJpegSize(void* buffer, unsigned int buffSize) { +int USBCamera::GetJpegSize(void* buffer, int buffSize) { uint8_t* data = static_cast(buffer); if (!wpi_assert(data[0] == 0xff && data[1] == 0xd8)) return 0; - unsigned int pos = 2; + int pos = 2; while (pos < buffSize) { // All control markers start with 0xff, so if this isn't present, // the JPEG is not valid if (!wpi_assert(data[pos] == 0xff)) return 0; - unsigned char t = data[pos + 1]; + int t = data[pos + 1]; // These are RST markers. We just skip them and move onto the next marker if (t == 0x01 || (t >= 0xd0 && t <= 0xd7)) { pos += 2; @@ -54,7 +54,8 @@ unsigned int USBCamera::GetJpegSize(void* buffer, unsigned int buffSize) { } else if (t == 0xda) { // SOS marker. The next two bytes are a 16-bit big-endian int that is // the length of the SOS header, skip that - unsigned int len = (data[pos + 2] & 0xffu) << 8 | (data[pos + 3] & 0xffu); + int len = (static_cast(data[pos + 2]) & 0xff) << 8 | + (static_cast(data[pos + 3]) & 0xff); pos += len + 2; // The next marker is the first marker that is 0xff followed by a non-RST // element. 0xff followed by 0x00 is an escaped 0xff. 0xd0-0xd7 are RST @@ -69,7 +70,8 @@ unsigned int USBCamera::GetJpegSize(void* buffer, unsigned int buffSize) { // 16-bit // big-endian int with the length of the marker header, skip that then // continue searching - unsigned int len = (data[pos + 2] & 0xffu) << 8 | (data[pos + 3] & 0xffu); + int len = (static_cast(data[pos + 2]) & 0xff) << 8 | + (static_cast(data[pos + 3]) & 0xff); pos += len + 2; } } @@ -82,7 +84,7 @@ USBCamera::USBCamera(std::string name, bool useJpeg) void USBCamera::OpenCamera() { std::lock_guard lock(m_mutex); - for (unsigned int i = 0; i < 3; i++) { + for (int i = 0; i < 3; i++) { uInt32 id = 0; // Can't use SAFE_IMAQ_CALL here because we only error on the third time IMAQdxError error = IMAQdxOpenCamera( @@ -151,11 +153,11 @@ void USBCamera::UpdateSettings() { double foundFps = 1000.0; // Loop through the modes, and find the match with the lowest fps - for (unsigned int i = 0; i < count; i++) { + for (uint32_t i = 0; i < count; i++) { std::cmatch m; if (!std::regex_match(modes[i].Name, m, reMode)) continue; - unsigned int width = static_cast(std::stoul(m[1].str())); - unsigned int height = static_cast(std::stoul(m[2].str())); + int width = static_cast(std::stoul(m[1].str())); + int height = static_cast(std::stoul(m[2].str())); if (width != m_width) continue; if (height != m_height) continue; double fps = atof(m[4].str().c_str()); @@ -230,7 +232,7 @@ void USBCamera::SetFPS(double fps) { } } -void USBCamera::SetSize(unsigned int width, unsigned int height) { +void USBCamera::SetSize(int width, int height) { std::lock_guard lock(m_mutex); if (m_width != width || m_height != height) { m_needSettingsUpdate = true; @@ -239,7 +241,7 @@ void USBCamera::SetSize(unsigned int width, unsigned int height) { } } -void USBCamera::SetBrightness(unsigned int brightness) { +void USBCamera::SetBrightness(int brightness) { std::lock_guard lock(m_mutex); if (m_brightness != brightness) { m_needSettingsUpdate = true; @@ -247,7 +249,7 @@ void USBCamera::SetBrightness(unsigned int brightness) { } } -unsigned int USBCamera::GetBrightness() { +int USBCamera::GetBrightness() { std::lock_guard lock(m_mutex); return m_brightness; } @@ -268,7 +270,7 @@ void USBCamera::SetWhiteBalanceHoldCurrent() { m_needSettingsUpdate = true; } -void USBCamera::SetWhiteBalanceManual(unsigned int whiteBalance) { +void USBCamera::SetWhiteBalanceManual(int whiteBalance) { std::lock_guard lock(m_mutex); m_whiteBalance = MANUAL; m_whiteBalanceValue = whiteBalance; @@ -292,7 +294,7 @@ void USBCamera::SetExposureHoldCurrent() { m_needSettingsUpdate = true; } -void USBCamera::SetExposureManual(unsigned int level) { +void USBCamera::SetExposureManual(int level) { std::lock_guard lock(m_mutex); m_exposure = MANUAL; if (level > 100) @@ -316,7 +318,7 @@ void USBCamera::GetImage(Image* image) { SAFE_IMAQ_CALL(IMAQdxGrab, m_id, image, 1, &bufNum); } -unsigned int USBCamera::GetImageData(void* buffer, unsigned int bufferSize) { +int USBCamera::GetImageData(void* buffer, int bufferSize) { std::lock_guard lock(m_mutex); if (m_needSettingsUpdate || !m_useJpeg) { m_needSettingsUpdate = false; diff --git a/wpilibc/athena/src/Ultrasonic.cpp b/wpilibc/athena/src/Ultrasonic.cpp index d4359a8d5e..5403d1f979 100644 --- a/wpilibc/athena/src/Ultrasonic.cpp +++ b/wpilibc/athena/src/Ultrasonic.cpp @@ -18,7 +18,7 @@ // Time (sec) for the ping trigger pulse. constexpr double Ultrasonic::kPingTime; // Priority that the ultrasonic round robin task runs. -const uint32_t Ultrasonic::kPriority; +const int Ultrasonic::kPriority; // Max time (ms) between readings. constexpr double Ultrasonic::kMaxUltrasonicTime; constexpr double Ultrasonic::kSpeedOfSoundInchesPerSec; @@ -91,8 +91,7 @@ void Ultrasonic::Initialize() { * round trip time of the ping, and the distance. * @param units The units returned in either kInches or kMilliMeters */ -Ultrasonic::Ultrasonic(uint32_t pingChannel, uint32_t echoChannel, - DistanceUnit units) +Ultrasonic::Ultrasonic(int pingChannel, int echoChannel, DistanceUnit units) : m_pingChannel(std::make_shared(pingChannel)), m_echoChannel(std::make_shared(echoChannel)), m_counter(m_echoChannel) { diff --git a/wpilibc/athena/src/Utility.cpp b/wpilibc/athena/src/Utility.cpp index c0b835b775..dace891281 100644 --- a/wpilibc/athena/src/Utility.cpp +++ b/wpilibc/athena/src/Utility.cpp @@ -23,8 +23,8 @@ * Utility.h. */ bool wpi_assert_impl(bool conditionValue, const char* conditionText, - const char* message, const char* fileName, - uint32_t lineNumber, const char* funcName) { + const char* message, const char* fileName, int lineNumber, + const char* funcName) { if (!conditionValue) { std::stringstream locStream; locStream << funcName << " ["; @@ -58,7 +58,7 @@ bool wpi_assert_impl(bool conditionValue, const char* conditionText, */ void wpi_assertEqual_common_impl(const char* valueA, const char* valueB, const char* equalityType, const char* message, - const char* fileName, uint32_t lineNumber, + const char* fileName, int lineNumber, const char* funcName) { std::stringstream locStream; locStream << funcName << " ["; @@ -92,7 +92,7 @@ void wpi_assertEqual_common_impl(const char* valueA, const char* valueB, */ bool wpi_assertEqual_impl(int valueA, int valueB, const char* valueAString, const char* valueBString, const char* message, - const char* fileName, uint32_t lineNumber, + const char* fileName, int lineNumber, const char* funcName) { if (!(valueA == valueB)) { wpi_assertEqual_common_impl(valueAString, valueBString, "==", message, @@ -110,7 +110,7 @@ bool wpi_assertEqual_impl(int valueA, int valueB, const char* valueAString, */ bool wpi_assertNotEqual_impl(int valueA, int valueB, const char* valueAString, const char* valueBString, const char* message, - const char* fileName, uint32_t lineNumber, + const char* fileName, int lineNumber, const char* funcName) { if (!(valueA != valueB)) { wpi_assertEqual_common_impl(valueAString, valueBString, "!=", message, @@ -125,9 +125,9 @@ bool wpi_assertNotEqual_impl(int valueA, int valueB, const char* valueAString, * For now, expect this to be competition year. * @return FPGA Version number. */ -int32_t GetFPGAVersion() { +int GetFPGAVersion() { int32_t status = 0; - int32_t version = HAL_GetFPGAVersion(&status); + int version = HAL_GetFPGAVersion(&status); wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status)); return version; } @@ -180,7 +180,7 @@ bool GetUserButton() { static std::string demangle(char const* mangledSymbol) { char buffer[256]; size_t length; - int status; + int32_t status; if (sscanf(mangledSymbol, "%*[^(]%*[(]%255[^)+]", buffer)) { char* symbol = abi::__cxa_demangle(buffer, nullptr, &length, &status); @@ -201,7 +201,7 @@ static std::string demangle(char const* mangledSymbol) { * Get a stack trace, ignoring the first "offset" symbols. * @param offset The number of symbols at the top of the stack to ignore */ -std::string GetStackTrace(uint32_t offset) { +std::string GetStackTrace(int offset) { void* stackTrace[128]; int stackSize = backtrace(stackTrace, 128); char** mangledSymbols = backtrace_symbols(stackTrace, stackSize); diff --git a/wpilibc/athena/src/Victor.cpp b/wpilibc/athena/src/Victor.cpp index 16ac12082a..107852c70b 100644 --- a/wpilibc/athena/src/Victor.cpp +++ b/wpilibc/athena/src/Victor.cpp @@ -16,7 +16,7 @@ * @param channel The PWM channel number that the Victor is attached to. 0-9 * are on-board, 10-19 are on the MXP port */ -Victor::Victor(uint32_t channel) : PWMSpeedController(channel) { +Victor::Victor(int channel) : PWMSpeedController(channel) { /* Note that the Victor uses the following bounds for PWM values. These * values were determined empirically and optimized for the Victor 888. These * values should work reasonably well for Victor 884 controllers as well but diff --git a/wpilibc/athena/src/VictorSP.cpp b/wpilibc/athena/src/VictorSP.cpp index 8888ed1b26..33f11e0e83 100644 --- a/wpilibc/athena/src/VictorSP.cpp +++ b/wpilibc/athena/src/VictorSP.cpp @@ -16,7 +16,7 @@ * @param channel The PWM channel that the VictorSP is attached to. 0-9 are * on-board, 10-19 are on the MXP port */ -VictorSP::VictorSP(uint32_t channel) : PWMSpeedController(channel) { +VictorSP::VictorSP(int channel) : PWMSpeedController(channel) { /** * Note that the VictorSP uses the following bounds for PWM values. These * values should work reasonably well for most controllers, but if users diff --git a/wpilibc/athena/src/Vision/AxisCamera.cpp b/wpilibc/athena/src/Vision/AxisCamera.cpp index d72532da25..9d7bcccc4e 100644 --- a/wpilibc/athena/src/Vision/AxisCamera.cpp +++ b/wpilibc/athena/src/Vision/AxisCamera.cpp @@ -20,8 +20,8 @@ #include "Timer.h" #include "WPIErrors.h" -static const unsigned int kMaxPacketSize = 1536; -static const unsigned int kImageBufferAllocationIncrement = 1000; +static const int kMaxPacketSize = 1536; +static const int kImageBufferAllocationIncrement = 1000; static const std::string kWhiteBalanceStrings[] = { "auto", "hold", "fixed_outdoor1", "fixed_outdoor2", @@ -123,8 +123,8 @@ HSLImage* AxisCamera::GetImage() { * @param numBytes The size of the destination image. * @return 0 if failed (no source image or no memory), 1 if success. */ -int AxisCamera::CopyJPEG(char** destImage, unsigned int& destImageSize, - unsigned int& destImageBufferSize) { +int AxisCamera::CopyJPEG(char** destImage, int& destImageSize, + int& destImageBufferSize) { std::lock_guard lock(m_imageDataMutex); if (destImage == nullptr) { wpi_setWPIErrorWithContext(NullParameter, "destImage must not be nullptr"); @@ -134,7 +134,7 @@ int AxisCamera::CopyJPEG(char** destImage, unsigned int& destImageSize, if (m_imageData.size() == 0) return 0; // if no source image // if current destination buffer too small - if (destImageBufferSize < m_imageData.size()) { + if (static_cast(destImageBufferSize) < m_imageData.size()) { if (*destImage != nullptr) delete[] * destImage; destImageBufferSize = m_imageData.size() + kImageBufferAllocationIncrement; *destImage = new char[destImageBufferSize]; diff --git a/wpilibc/athena/src/Vision/VisionAPI.cpp b/wpilibc/athena/src/Vision/VisionAPI.cpp index 9e8cbc8d8f..4223fb9050 100644 --- a/wpilibc/athena/src/Vision/VisionAPI.cpp +++ b/wpilibc/athena/src/Vision/VisionAPI.cpp @@ -622,19 +622,18 @@ int frcColorEqualize(Image* dest, const Image* source, int colorEqualization) { * @return On success: 1. On failure: 0. To get extended error information, call * GetLastError(). */ -int frcSmartThreshold(Image* dest, const Image* source, - unsigned int windowWidth, unsigned int windowHeight, - LocalThresholdMethod method, double deviationWeight, - ObjectType type) { +int frcSmartThreshold(Image* dest, const Image* source, int windowWidth, + int windowHeight, LocalThresholdMethod method, + double deviationWeight, ObjectType type) { float replaceValue = 1.0; return imaqLocalThreshold(dest, source, windowWidth, windowHeight, method, deviationWeight, type, replaceValue); } -int frcSmartThreshold(Image* dest, const Image* source, - unsigned int windowWidth, unsigned int windowHeight, - LocalThresholdMethod method, double deviationWeight, - ObjectType type, float replaceValue) { +int frcSmartThreshold(Image* dest, const Image* source, int windowWidth, + int windowHeight, LocalThresholdMethod method, + double deviationWeight, ObjectType type, + float replaceValue) { return imaqLocalThreshold(dest, source, windowWidth, windowHeight, method, deviationWeight, type, replaceValue); } diff --git a/wpilibc/shared/include/Error.h b/wpilibc/shared/include/Error.h index 73f12acb41..1d9e5bbf5d 100644 --- a/wpilibc/shared/include/Error.h +++ b/wpilibc/shared/include/Error.h @@ -28,7 +28,7 @@ class ErrorBase; */ class Error { public: - typedef int32_t Code; + typedef int Code; Error() = default; @@ -40,12 +40,12 @@ class Error { std::string GetMessage() const; std::string GetFilename() const; std::string GetFunction() const; - uint32_t GetLineNumber() const; + int GetLineNumber() const; const ErrorBase* GetOriginatingObject() const; double GetTimestamp() const; void Clear(); void Set(Code code, llvm::StringRef contextMessage, llvm::StringRef filename, - llvm::StringRef function, uint32_t lineNumber, + llvm::StringRef function, int lineNumber, const ErrorBase* originatingObject); private: @@ -55,7 +55,7 @@ class Error { std::string m_message; std::string m_filename; std::string m_function; - uint32_t m_lineNumber = 0; + int m_lineNumber = 0; const ErrorBase* m_originatingObject = nullptr; double m_timestamp = 0.0; }; diff --git a/wpilibc/shared/include/ErrorBase.h b/wpilibc/shared/include/ErrorBase.h index 5277a1528e..489c2ea1b6 100644 --- a/wpilibc/shared/include/ErrorBase.h +++ b/wpilibc/shared/include/ErrorBase.h @@ -81,32 +81,32 @@ class ErrorBase { virtual const Error& GetError() const; virtual void SetErrnoError(llvm::StringRef contextMessage, llvm::StringRef filename, llvm::StringRef function, - uint32_t lineNumber) const; + int lineNumber) const; virtual void SetImaqError(int success, llvm::StringRef contextMessage, llvm::StringRef filename, llvm::StringRef function, - uint32_t lineNumber) const; + int lineNumber) const; virtual void SetError(Error::Code code, llvm::StringRef contextMessage, llvm::StringRef filename, llvm::StringRef function, - uint32_t lineNumber) const; + int lineNumber) const; virtual void SetErrorRange(Error::Code code, int32_t minRange, int32_t maxRange, int32_t requestedValue, llvm::StringRef contextMessage, llvm::StringRef filename, llvm::StringRef function, - uint32_t lineNumber) const; + int lineNumber) const; virtual void SetWPIError(llvm::StringRef errorMessage, Error::Code code, llvm::StringRef contextMessage, llvm::StringRef filename, llvm::StringRef function, - uint32_t lineNumber) const; + int lineNumber) const; virtual void CloneError(const ErrorBase& rhs) const; virtual void ClearError() const; virtual bool StatusIsFatal() const; static void SetGlobalError(Error::Code code, llvm::StringRef contextMessage, llvm::StringRef filename, llvm::StringRef function, - uint32_t lineNumber); + int lineNumber); static void SetGlobalWPIError(llvm::StringRef errorMessage, llvm::StringRef contextMessage, llvm::StringRef filename, - llvm::StringRef function, uint32_t lineNumber); + llvm::StringRef function, int lineNumber); static Error& GetGlobalError(); protected: diff --git a/wpilibc/shared/include/Filters/LinearDigitalFilter.h b/wpilibc/shared/include/Filters/LinearDigitalFilter.h index 325a1bc629..0766f29bdc 100644 --- a/wpilibc/shared/include/Filters/LinearDigitalFilter.h +++ b/wpilibc/shared/include/Filters/LinearDigitalFilter.h @@ -84,7 +84,7 @@ class LinearDigitalFilter : public Filter { static LinearDigitalFilter HighPass(std::shared_ptr source, double timeConstant, double period); static LinearDigitalFilter MovingAverage(std::shared_ptr source, - unsigned int taps); + int taps); // Filter interface double Get() const override; diff --git a/wpilibc/shared/include/GenericHID.h b/wpilibc/shared/include/GenericHID.h index 57497f2b16..68602c7557 100644 --- a/wpilibc/shared/include/GenericHID.h +++ b/wpilibc/shared/include/GenericHID.h @@ -23,12 +23,12 @@ class GenericHID { virtual float GetZ() const = 0; virtual float GetTwist() const = 0; virtual float GetThrottle() const = 0; - virtual float GetRawAxis(uint32_t axis) const = 0; + virtual float GetRawAxis(int axis) const = 0; virtual bool GetTrigger(JoystickHand hand = kRightHand) const = 0; virtual bool GetTop(JoystickHand hand = kRightHand) const = 0; virtual bool GetBumper(JoystickHand hand = kRightHand) const = 0; - virtual bool GetRawButton(uint32_t button) const = 0; + virtual bool GetRawButton(int button) const = 0; - virtual int GetPOV(uint32_t pov = 0) const = 0; + virtual int GetPOV(int pov = 0) const = 0; }; diff --git a/wpilibc/shared/include/PIDController.h b/wpilibc/shared/include/PIDController.h index 9d10794d01..79dfebdc45 100644 --- a/wpilibc/shared/include/PIDController.h +++ b/wpilibc/shared/include/PIDController.h @@ -70,7 +70,7 @@ class PIDController : public LiveWindowSendable, virtual void SetTolerance(float percent); virtual void SetAbsoluteTolerance(float absValue); virtual void SetPercentTolerance(float percentValue); - virtual void SetToleranceBuffer(unsigned buf = 1); + virtual void SetToleranceBuffer(int buf = 1); virtual bool OnTarget() const; void Enable() override; diff --git a/wpilibc/shared/include/Task.h b/wpilibc/shared/include/Task.h index cb70d96b33..2731b7380d 100644 --- a/wpilibc/shared/include/Task.h +++ b/wpilibc/shared/include/Task.h @@ -18,7 +18,7 @@ */ class Task : public ErrorBase { public: - static const uint32_t kDefaultPriority = 60; + static const int kDefaultPriority = 60; Task() = default; Task(const Task&) = delete; @@ -38,9 +38,9 @@ class Task : public ErrorBase { bool Verify(); - int32_t GetPriority(); + int GetPriority(); - bool SetPriority(int32_t priority); + bool SetPriority(int priority); std::string GetName() const; diff --git a/wpilibc/shared/include/Utility.h b/wpilibc/shared/include/Utility.h index d3e58937d7..0d24d3d656 100644 --- a/wpilibc/shared/include/Utility.h +++ b/wpilibc/shared/include/Utility.h @@ -32,21 +32,21 @@ __FUNCTION__) bool wpi_assert_impl(bool conditionValue, const char* conditionText, - const char* message, const char* fileName, - uint32_t lineNumber, const char* funcName); + const char* message, const char* fileName, int lineNumber, + const char* funcName); bool wpi_assertEqual_impl(int valueA, int valueB, const char* valueAString, const char* valueBString, const char* message, - const char* fileName, uint32_t lineNumber, + const char* fileName, int lineNumber, const char* funcName); bool wpi_assertNotEqual_impl(int valueA, int valueB, const char* valueAString, const char* valueBString, const char* message, - const char* fileName, uint32_t lineNumber, + const char* fileName, int lineNumber, const char* funcName); void wpi_suspendOnAssertEnabled(bool enabled); -int32_t GetFPGAVersion(); +int GetFPGAVersion(); int64_t GetFPGARevision(); uint64_t GetFPGATime(); bool GetUserButton(); -std::string GetStackTrace(uint32_t offset); +std::string GetStackTrace(int offset); diff --git a/wpilibc/shared/include/WPIErrors.h b/wpilibc/shared/include/WPIErrors.h index 0a73a7adae..bc948c9d98 100644 --- a/wpilibc/shared/include/WPIErrors.h +++ b/wpilibc/shared/include/WPIErrors.h @@ -12,11 +12,11 @@ #ifdef WPI_ERRORS_DEFINE_STRINGS #define S(label, offset, message) \ const char* wpi_error_s_##label = message; \ - const int32_t wpi_error_value_##label = offset + const int wpi_error_value_##label = offset #else #define S(label, offset, message) \ extern const char* wpi_error_s_##label; \ - const int32_t wpi_error_value_##label = offset + const int wpi_error_value_##label = offset #endif /* diff --git a/wpilibc/shared/src/Commands/Scheduler.cpp b/wpilibc/shared/src/Commands/Scheduler.cpp index 8525a91dc5..0ec8f72e18 100644 --- a/wpilibc/shared/src/Commands/Scheduler.cpp +++ b/wpilibc/shared/src/Commands/Scheduler.cpp @@ -232,7 +232,7 @@ void Scheduler::UpdateTable() { if (!toCancel.empty()) { for (commandIter = m_commands.begin(); commandIter != m_commands.end(); ++commandIter) { - for (unsigned i = 0; i < toCancel.size(); i++) { + for (size_t i = 0; i < toCancel.size(); i++) { Command* c = *commandIter; if (c->GetID() == toCancel[i]) { c->Cancel(); diff --git a/wpilibc/shared/src/Error.cpp b/wpilibc/shared/src/Error.cpp index 8c0212f6f1..86bce8aba2 100644 --- a/wpilibc/shared/src/Error.cpp +++ b/wpilibc/shared/src/Error.cpp @@ -31,7 +31,7 @@ std::string Error::GetFilename() const { return m_filename; } std::string Error::GetFunction() const { return m_function; } -uint32_t Error::GetLineNumber() const { return m_lineNumber; } +int Error::GetLineNumber() const { return m_lineNumber; } const ErrorBase* Error::GetOriginatingObject() const { return m_originatingObject; @@ -41,7 +41,7 @@ double Error::GetTimestamp() const { return m_timestamp; } void Error::Set(Code code, llvm::StringRef contextMessage, llvm::StringRef filename, llvm::StringRef function, - uint32_t lineNumber, const ErrorBase* originatingObject) { + int lineNumber, const ErrorBase* originatingObject) { bool report = true; if (code == m_code && GetTime() - m_timestamp < 1) { diff --git a/wpilibc/shared/src/ErrorBase.cpp b/wpilibc/shared/src/ErrorBase.cpp index f7ce1d197d..d3ec716b99 100644 --- a/wpilibc/shared/src/ErrorBase.cpp +++ b/wpilibc/shared/src/ErrorBase.cpp @@ -41,8 +41,7 @@ void ErrorBase::ClearError() const { m_error.Clear(); } */ void ErrorBase::SetErrnoError(llvm::StringRef contextMessage, llvm::StringRef filename, - llvm::StringRef function, - uint32_t lineNumber) const { + llvm::StringRef function, int lineNumber) const { std::string err; int errNo = errno; if (errNo == 0) { @@ -77,7 +76,7 @@ void ErrorBase::SetErrnoError(llvm::StringRef contextMessage, */ void ErrorBase::SetImaqError(int success, llvm::StringRef contextMessage, llvm::StringRef filename, llvm::StringRef function, - uint32_t lineNumber) const { + int lineNumber) const { // If there was an error if (success <= 0) { std::stringstream err; @@ -105,7 +104,7 @@ void ErrorBase::SetImaqError(int success, llvm::StringRef contextMessage, */ void ErrorBase::SetError(Error::Code code, llvm::StringRef contextMessage, llvm::StringRef filename, llvm::StringRef function, - uint32_t lineNumber) const { + int lineNumber) const { // If there was an error if (code != 0) { // Set the current error information for this object. @@ -136,8 +135,7 @@ void ErrorBase::SetErrorRange(Error::Code code, int32_t minRange, int32_t maxRange, int32_t requestedValue, llvm::StringRef contextMessage, llvm::StringRef filename, - llvm::StringRef function, - uint32_t lineNumber) const { + llvm::StringRef function, int lineNumber) const { // If there was an error if (code != 0) { size_t size = contextMessage.size() + 100; @@ -169,7 +167,7 @@ void ErrorBase::SetErrorRange(Error::Code code, int32_t minRange, void ErrorBase::SetWPIError(llvm::StringRef errorMessage, Error::Code code, llvm::StringRef contextMessage, llvm::StringRef filename, llvm::StringRef function, - uint32_t lineNumber) const { + int lineNumber) const { std::string err = errorMessage.str() + ": " + contextMessage.str(); // Set the current error information for this object. @@ -195,7 +193,7 @@ bool ErrorBase::StatusIsFatal() const { return m_error.GetCode() < 0; } void ErrorBase::SetGlobalError(Error::Code code, llvm::StringRef contextMessage, llvm::StringRef filename, - llvm::StringRef function, uint32_t lineNumber) { + llvm::StringRef function, int lineNumber) { // If there was an error if (code != 0) { std::lock_guard mutex(_globalErrorMutex); @@ -209,8 +207,7 @@ void ErrorBase::SetGlobalError(Error::Code code, llvm::StringRef contextMessage, void ErrorBase::SetGlobalWPIError(llvm::StringRef errorMessage, llvm::StringRef contextMessage, llvm::StringRef filename, - llvm::StringRef function, - uint32_t lineNumber) { + llvm::StringRef function, int lineNumber) { std::string err = errorMessage.str() + ": " + contextMessage.str(); std::lock_guard mutex(_globalErrorMutex); diff --git a/wpilibc/shared/src/Filters/LinearDigitalFilter.cpp b/wpilibc/shared/src/Filters/LinearDigitalFilter.cpp index 2a899c468f..bd643700b6 100644 --- a/wpilibc/shared/src/Filters/LinearDigitalFilter.cpp +++ b/wpilibc/shared/src/Filters/LinearDigitalFilter.cpp @@ -119,7 +119,7 @@ LinearDigitalFilter LinearDigitalFilter::HighPass( * slower */ LinearDigitalFilter LinearDigitalFilter::MovingAverage( - std::shared_ptr source, unsigned int taps) { + std::shared_ptr source, int taps) { assert(taps > 0); std::vector gains(taps, 1.0 / taps); @@ -130,10 +130,10 @@ double LinearDigitalFilter::Get() const { double retVal = 0.0; // Calculate the new value - for (unsigned int i = 0; i < m_inputGains.size(); i++) { + for (size_t i = 0; i < m_inputGains.size(); i++) { retVal += m_inputs[i] * m_inputGains[i]; } - for (unsigned int i = 0; i < m_outputGains.size(); i++) { + for (size_t i = 0; i < m_outputGains.size(); i++) { retVal -= m_outputs[i] * m_outputGains[i]; } @@ -157,10 +157,10 @@ double LinearDigitalFilter::PIDGet() { m_inputs.PushFront(PIDGetSource()); // Calculate the new value - for (unsigned int i = 0; i < m_inputGains.size(); i++) { + for (size_t i = 0; i < m_inputGains.size(); i++) { retVal += m_inputs[i] * m_inputGains[i]; } - for (unsigned int i = 0; i < m_outputGains.size(); i++) { + for (size_t i = 0; i < m_outputGains.size(); i++) { retVal -= m_outputs[i] * m_outputGains[i]; } diff --git a/wpilibc/sim/include/AnalogGyro.h b/wpilibc/sim/include/AnalogGyro.h index 11ece7b07d..fb04be285b 100644 --- a/wpilibc/sim/include/AnalogGyro.h +++ b/wpilibc/sim/include/AnalogGyro.h @@ -29,13 +29,13 @@ class AnalogModule; */ class AnalogGyro : public GyroBase { public: - static const uint32_t kOversampleBits; - static const uint32_t kAverageBits; + static const int kOversampleBits; + static const int kAverageBits; static const float kSamplesPerSecond; static const float kCalibrationSampleTime; static const float kDefaultVoltsPerDegreePerSecond; - explicit AnalogGyro(uint32_t channel); + explicit AnalogGyro(int channel); virtual ~AnalogGyro() = default; float GetAngle() const; void Calibrate() override; diff --git a/wpilibc/sim/include/AnalogInput.h b/wpilibc/sim/include/AnalogInput.h index d6c5c21c84..a8e6676c69 100644 --- a/wpilibc/sim/include/AnalogInput.h +++ b/wpilibc/sim/include/AnalogInput.h @@ -31,17 +31,17 @@ class AnalogInput : public SensorBase, public PIDSource, public LiveWindowSendable { public: - static const uint8_t kAccumulatorModuleNumber = 1; - static const uint32_t kAccumulatorNumChannels = 2; - static const uint32_t kAccumulatorChannels[kAccumulatorNumChannels]; + static const int kAccumulatorModuleNumber = 1; + static const int kAccumulatorNumChannels = 2; + static const int kAccumulatorChannels[kAccumulatorNumChannels]; - explicit AnalogInput(uint32_t channel); + explicit AnalogInput(int channel); virtual ~AnalogInput() = default; float GetVoltage() const; float GetAverageVoltage() const; - uint32_t GetChannel() const; + int GetChannel() const; double PIDGet() override; @@ -53,7 +53,7 @@ class AnalogInput : public SensorBase, std::shared_ptr GetTable() const override; private: - uint32_t m_channel; + int m_channel; SimFloatInput* m_impl; int64_t m_accumulatorOffset; diff --git a/wpilibc/sim/include/Counter.h b/wpilibc/sim/include/Counter.h index 2ec0724244..5b9b505e64 100644 --- a/wpilibc/sim/include/Counter.h +++ b/wpilibc/sim/include/Counter.h @@ -29,7 +29,7 @@ class Counter : public SensorBase, public LiveWindowSendable { public: explicit Counter(Mode mode = kTwoPulse); - explicit Counter(uint32_t channel); + explicit Counter(int channel); // TODO: [Not Supported] explicit Counter(DigitalSource *source); // TODO: [Not Supported] explicit Counter(DigitalSource &source); // TODO: [Not Supported] explicit Counter(AnalogTrigger *source); @@ -38,7 +38,7 @@ class Counter : public SensorBase, // *upSource, DigitalSource *downSource, bool inverted); virtual ~Counter(); - void SetUpSource(uint32_t channel); + void SetUpSource(int channel); // TODO: [Not Supported] void SetUpSource(AnalogTrigger *analogTrigger, // AnalogTriggerType triggerType); // TODO: [Not Supported] void SetUpSource(AnalogTrigger &analogTrigger, @@ -48,7 +48,7 @@ class Counter : public SensorBase, void SetUpSourceEdge(bool risingEdge, bool fallingEdge); void ClearUpSource(); - void SetDownSource(uint32_t channel); + void SetDownSource(int channel); // TODO: [Not Supported] void SetDownSource(AnalogTrigger *analogTrigger, // AnalogTriggerType triggerType); // TODO: [Not Supported] void SetDownSource(AnalogTrigger &analogTrigger, @@ -66,7 +66,7 @@ class Counter : public SensorBase, void SetReverseDirection(bool reverseDirection); // CounterBase interface - int32_t Get() const override; + int Get() const override; void Reset() override; double GetPeriod() const override; void SetMaxPeriod(double maxPeriod) override; @@ -76,7 +76,7 @@ class Counter : public SensorBase, void SetSamplesToAverage(int samplesToAverage); int GetSamplesToAverage() const; - uint32_t GetFPGAIndex() const { return m_index; } + int GetFPGAIndex() const { return m_index; } void UpdateTable() override; void StartLiveWindowMode() override; @@ -94,7 +94,7 @@ class Counter : public SensorBase, private: bool m_allocatedUpSource; ///< Was the upSource allocated locally? bool m_allocatedDownSource; ///< Was the downSource allocated locally? - uint32_t m_index; ///< The index of this counter. + int m_index; ///< The index of this counter. std::shared_ptr m_table; }; diff --git a/wpilibc/sim/include/CounterBase.h b/wpilibc/sim/include/CounterBase.h index 09a71356ad..484535c829 100644 --- a/wpilibc/sim/include/CounterBase.h +++ b/wpilibc/sim/include/CounterBase.h @@ -21,7 +21,7 @@ class CounterBase { enum EncodingType { k1X, k2X, k4X }; virtual ~CounterBase() = default; - virtual int32_t Get() const = 0; + virtual int Get() const = 0; virtual void Reset() = 0; virtual double GetPeriod() const = 0; virtual void SetMaxPeriod(double maxPeriod) = 0; diff --git a/wpilibc/sim/include/DigitalInput.h b/wpilibc/sim/include/DigitalInput.h index 2d68f0d22d..e1728b069b 100644 --- a/wpilibc/sim/include/DigitalInput.h +++ b/wpilibc/sim/include/DigitalInput.h @@ -24,10 +24,10 @@ */ class DigitalInput : public LiveWindowSendable { public: - explicit DigitalInput(uint32_t channel); + explicit DigitalInput(int channel); virtual ~DigitalInput() = default; - uint32_t Get() const; - uint32_t GetChannel() const; + int Get() const; + int GetChannel() const; void UpdateTable() override; void StartLiveWindowMode() override; @@ -37,7 +37,7 @@ class DigitalInput : public LiveWindowSendable { std::shared_ptr GetTable() const override; private: - uint32_t m_channel; + int m_channel; bool m_lastValue; SimDigitalInput* m_impl; diff --git a/wpilibc/sim/include/DoubleSolenoid.h b/wpilibc/sim/include/DoubleSolenoid.h index 02a5558558..8340c048a4 100644 --- a/wpilibc/sim/include/DoubleSolenoid.h +++ b/wpilibc/sim/include/DoubleSolenoid.h @@ -25,9 +25,8 @@ class DoubleSolenoid : public LiveWindowSendable, public ITableListener { public: enum Value { kOff, kForward, kReverse }; - explicit DoubleSolenoid(uint32_t forwardChannel, uint32_t reverseChannel); - DoubleSolenoid(uint8_t moduleNumber, uint32_t forwardChannel, - uint32_t reverseChannel); + explicit DoubleSolenoid(int forwardChannel, int reverseChannel); + DoubleSolenoid(int moduleNumber, int forwardChannel, int reverseChannel); virtual ~DoubleSolenoid(); virtual void Set(Value value); virtual Value Get() const; diff --git a/wpilibc/sim/include/DriverStation.h b/wpilibc/sim/include/DriverStation.h index 5aea6ba81a..59729ab771 100644 --- a/wpilibc/sim/include/DriverStation.h +++ b/wpilibc/sim/include/DriverStation.h @@ -40,22 +40,22 @@ class DriverStation : public SensorBase, public RobotStateInterface { static DriverStation& GetInstance(); static void ReportError(std::string error); static void ReportWarning(std::string error); - static void ReportError(bool is_error, int32_t code, const std::string& error, + static void ReportError(bool is_error, int code, const std::string& error, const std::string& location, const std::string& stack); - static const uint32_t kBatteryChannel = 7; - static const uint32_t kJoystickPorts = 4; - static const uint32_t kJoystickAxes = 6; + static const int kBatteryChannel = 7; + static const int kJoystickPorts = 4; + static const int kJoystickAxes = 6; - float GetStickAxis(uint32_t stick, uint32_t axis); - bool GetStickButton(uint32_t stick, uint32_t button); - int16_t GetStickButtons(uint32_t stick); + float GetStickAxis(int stick, int axis); + bool GetStickButton(int stick, int button); + int16_t GetStickButtons(int stick); - float GetAnalogIn(uint32_t channel); - bool GetDigitalIn(uint32_t channel); - void SetDigitalOut(uint32_t channel, bool value); - bool GetDigitalOut(uint32_t channel); + float GetAnalogIn(int channel); + bool GetDigitalIn(int channel); + void SetDigitalOut(int channel, bool value); + bool GetDigitalOut(int channel); bool IsEnabled() const; bool IsDisabled() const; @@ -64,9 +64,9 @@ class DriverStation : public SensorBase, public RobotStateInterface { bool IsTest() const; bool IsFMSAttached() const; - uint32_t GetPacketNumber() const; + int GetPacketNumber() const; Alliance GetAlliance() const; - uint32_t GetLocation() const; + int GetLocation() const; void WaitForData(); double GetMatchTime() const; float GetBatteryVoltage() const; @@ -112,7 +112,7 @@ class DriverStation : public SensorBase, public RobotStateInterface { private: static void InitTask(DriverStation* ds); static DriverStation* m_instance; - static uint8_t m_updateNumber; + static int m_updateNumber; ///< TODO: Get rid of this and use the semaphore signaling static const float kUpdatePeriod; @@ -125,7 +125,7 @@ class DriverStation : public SensorBase, public RobotStateInterface { void joystickCallback4(const msgs::ConstFRCJoystickPtr& msg); void joystickCallback5(const msgs::ConstFRCJoystickPtr& msg); - uint8_t m_digitalOut = 0; + int m_digitalOut = 0; std::condition_variable m_waitForDataCond; std::mutex m_waitForDataMutex; mutable std::recursive_mutex m_stateMutex; diff --git a/wpilibc/sim/include/Encoder.h b/wpilibc/sim/include/Encoder.h index de03a8ac7d..90d6268113 100644 --- a/wpilibc/sim/include/Encoder.h +++ b/wpilibc/sim/include/Encoder.h @@ -38,7 +38,7 @@ class Encoder : public SensorBase, public PIDSource, public LiveWindowSendable { public: - Encoder(uint32_t aChannel, uint32_t bChannel, bool reverseDirection = false, + Encoder(int aChannel, int bChannel, bool reverseDirection = false, EncodingType encodingType = k4X); // TODO: [Not Supported] Encoder(DigitalSource *aSource, DigitalSource // *bSource, bool reverseDirection=false, EncodingType encodingType = k4X); @@ -47,9 +47,9 @@ class Encoder : public SensorBase, virtual ~Encoder() = default; // CounterBase interface - int32_t Get() const override; - int32_t GetRaw() const; - int32_t GetEncodingScale() const; + int Get() const override; + int GetRaw() const; + int GetEncodingScale() const; void Reset() override; double GetPeriod() const override; void SetMaxPeriod(double maxPeriod) override; @@ -73,7 +73,7 @@ class Encoder : public SensorBase, void InitTable(std::shared_ptr subTable) override; std::shared_ptr GetTable() const override; - int32_t FPGAEncoderIndex() const { return 0; } + int FPGAEncoderIndex() const { return 0; } private: void InitEncoder(int channelA, int channelB, bool _reverseDirection, @@ -91,7 +91,7 @@ class Encoder : public SensorBase, int channelA, channelB; double m_distancePerPulse; // distance of travel for each encoder tick EncodingType m_encodingType; // Encoding type - int32_t m_encodingScale; // 1x, 2x, or 4x, per the encodingType + int m_encodingScale; // 1x, 2x, or 4x, per the encodingType bool m_reverseDirection; SimEncoder* impl; diff --git a/wpilibc/sim/include/Jaguar.h b/wpilibc/sim/include/Jaguar.h index d412686d02..af2d099899 100644 --- a/wpilibc/sim/include/Jaguar.h +++ b/wpilibc/sim/include/Jaguar.h @@ -16,7 +16,7 @@ */ class Jaguar : public SafePWM, public SpeedController { public: - explicit Jaguar(uint32_t channel); + explicit Jaguar(int channel); virtual ~Jaguar() = default; virtual void Set(float value); virtual float Get() const; diff --git a/wpilibc/sim/include/Joystick.h b/wpilibc/sim/include/Joystick.h index 3a99a9b213..584137a93e 100644 --- a/wpilibc/sim/include/Joystick.h +++ b/wpilibc/sim/include/Joystick.h @@ -23,11 +23,11 @@ class DriverStation; */ class Joystick : public GenericHID, public ErrorBase { public: - static const uint32_t kDefaultXAxis = 1; - static const uint32_t kDefaultYAxis = 2; - static const uint32_t kDefaultZAxis = 3; - static const uint32_t kDefaultTwistAxis = 4; - static const uint32_t kDefaultThrottleAxis = 3; + static const int kDefaultXAxis = 1; + static const int kDefaultYAxis = 2; + static const int kDefaultZAxis = 3; + static const int kDefaultTwistAxis = 4; + static const int kDefaultThrottleAxis = 3; typedef enum { kXAxis, kYAxis, @@ -36,19 +36,19 @@ class Joystick : public GenericHID, public ErrorBase { kThrottleAxis, kNumAxisTypes } AxisType; - static const uint32_t kDefaultTriggerButton = 1; - static const uint32_t kDefaultTopButton = 2; + static const int kDefaultTriggerButton = 1; + static const int kDefaultTopButton = 2; typedef enum { kTriggerButton, kTopButton, kNumButtonTypes } ButtonType; - explicit Joystick(uint32_t port); - Joystick(uint32_t port, uint32_t numAxisTypes, uint32_t numButtonTypes); + explicit Joystick(int port); + Joystick(int port, int numAxisTypes, int numButtonTypes); virtual ~Joystick() = default; Joystick(const Joystick&) = delete; Joystick& operator=(const Joystick&) = delete; - uint32_t GetAxisChannel(AxisType axis); - void SetAxisChannel(AxisType axis, uint32_t channel); + int GetAxisChannel(AxisType axis); + void SetAxisChannel(AxisType axis, int channel); float GetX(JoystickHand hand = kRightHand) const override; float GetY(JoystickHand hand = kRightHand) const override; @@ -56,15 +56,15 @@ class Joystick : public GenericHID, public ErrorBase { float GetTwist() const override; float GetThrottle() const override; virtual float GetAxis(AxisType axis) const; - float GetRawAxis(uint32_t axis) const override; + float GetRawAxis(int axis) const override; bool GetTrigger(JoystickHand hand = kRightHand) const override; bool GetTop(JoystickHand hand = kRightHand) const override; bool GetBumper(JoystickHand hand = kRightHand) const override; - bool GetRawButton(uint32_t button) const override; - int GetPOV(uint32_t pov = 1) const override; + bool GetRawButton(int button) const override; + int GetPOV(int pov = 1) const override; bool GetButton(ButtonType button) const; - static Joystick* GetStickForPort(uint32_t port); + static Joystick* GetStickForPort(int port); virtual float GetMagnitude() const; virtual float GetDirectionRadians() const; @@ -72,7 +72,7 @@ class Joystick : public GenericHID, public ErrorBase { private: DriverStation& m_ds; - uint32_t m_port; - std::unique_ptr m_axes; - std::unique_ptr m_buttons; + int m_port; + std::unique_ptr m_axes; + std::unique_ptr m_buttons; }; diff --git a/wpilibc/sim/include/Notifier.h b/wpilibc/sim/include/Notifier.h index a75e69d518..d9778c5c63 100644 --- a/wpilibc/sim/include/Notifier.h +++ b/wpilibc/sim/include/Notifier.h @@ -43,7 +43,7 @@ class Notifier : public ErrorBase { static std::atomic refcount; // Process the timer queue on a timer event - static void ProcessQueue(uint32_t mask, void* params); + static void ProcessQueue(int mask, void* params); // Update the FPGA alarm since the queue has changed static void UpdateAlarm(); diff --git a/wpilibc/sim/include/PWM.h b/wpilibc/sim/include/PWM.h index 5476339a80..d57e5a3ad8 100644 --- a/wpilibc/sim/include/PWM.h +++ b/wpilibc/sim/include/PWM.h @@ -42,16 +42,16 @@ class PWM : public SensorBase, kPeriodMultiplier_4X = 4 }; - explicit PWM(uint32_t channel); + explicit PWM(int channel); virtual ~PWM(); virtual void SetRaw(uint16_t value); void SetPeriodMultiplier(PeriodMultiplier mult); void EnableDeadbandElimination(bool eliminateDeadband); - void SetBounds(int32_t max, int32_t deadbandMax, int32_t center, - int32_t deadbandMin, int32_t min); + void SetBounds(int max, int deadbandMax, int center, int deadbandMin, + int min); void SetBounds(double max, double deadbandMax, double center, double deadbandMin, double min); - uint32_t GetChannel() const { return m_channel; } + int GetChannel() const { return m_channel; } protected: /** @@ -80,8 +80,8 @@ class PWM : public SensorBase, /** * kDefaultPWMStepsDown is the number of PWM steps below the centerpoint */ - static const int32_t kDefaultPwmStepsDown; - static const int32_t kPwmDisabled; + static const int kDefaultPwmStepsDown; + static const int kPwmDisabled; virtual void SetPosition(float pos); virtual float GetPosition() const; @@ -89,7 +89,7 @@ class PWM : public SensorBase, virtual float GetSpeed() const; bool m_eliminateDeadband; - int32_t m_centerPwm; + int m_centerPwm; void ValueChanged(ITable* source, llvm::StringRef key, std::shared_ptr value, bool isNew) override; @@ -103,6 +103,6 @@ class PWM : public SensorBase, std::shared_ptr m_table; private: - uint32_t m_channel; + int m_channel; SimContinuousOutput* impl; }; diff --git a/wpilibc/sim/include/Relay.h b/wpilibc/sim/include/Relay.h index 934f16abef..64f15803cc 100644 --- a/wpilibc/sim/include/Relay.h +++ b/wpilibc/sim/include/Relay.h @@ -40,12 +40,12 @@ class Relay : public MotorSafety, enum Value { kOff, kOn, kForward, kReverse }; enum Direction { kBothDirections, kForwardOnly, kReverseOnly }; - explicit Relay(uint32_t channel, Direction direction = kBothDirections); + explicit Relay(int channel, Direction direction = kBothDirections); virtual ~Relay(); void Set(Value value); Value Get() const; - uint32_t GetChannel() const; + int GetChannel() const; void SetExpiration(float timeout) override; float GetExpiration() const override; @@ -67,7 +67,7 @@ class Relay : public MotorSafety, std::shared_ptr m_table; private: - uint32_t m_channel; + int m_channel; Direction m_direction; std::unique_ptr m_safetyHelper; SimContinuousOutput* impl; diff --git a/wpilibc/sim/include/RobotDrive.h b/wpilibc/sim/include/RobotDrive.h index 2008aa071b..6383dcc0d3 100644 --- a/wpilibc/sim/include/RobotDrive.h +++ b/wpilibc/sim/include/RobotDrive.h @@ -38,9 +38,9 @@ class RobotDrive : public MotorSafety, public ErrorBase { kRearRightMotor = 3 }; - RobotDrive(uint32_t leftMotorChannel, uint32_t rightMotorChannel); - RobotDrive(uint32_t frontLeftMotorChannel, uint32_t rearLeftMotorChannel, - uint32_t frontRightMotorChannel, uint32_t rearRightMotorChannel); + RobotDrive(int leftMotorChannel, int rightMotorChannel); + RobotDrive(int frontLeftMotorChannel, int rearLeftMotorChannel, + int frontRightMotorChannel, int rearRightMotorChannel); RobotDrive(SpeedController* leftMotor, SpeedController* rightMotor); RobotDrive(SpeedController& leftMotor, SpeedController& rightMotor); RobotDrive(std::shared_ptr leftMotor, @@ -63,20 +63,18 @@ class RobotDrive : public MotorSafety, public ErrorBase { bool squaredInputs = true); void TankDrive(GenericHID& leftStick, GenericHID& rightStick, bool squaredInputs = true); - void TankDrive(GenericHID* leftStick, uint32_t leftAxis, - GenericHID* rightStick, uint32_t rightAxis, - bool squaredInputs = true); - void TankDrive(GenericHID& leftStick, uint32_t leftAxis, - GenericHID& rightStick, uint32_t rightAxis, - bool squaredInputs = true); + void TankDrive(GenericHID* leftStick, int leftAxis, GenericHID* rightStick, + 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 ArcadeDrive(GenericHID* stick, bool squaredInputs = true); void ArcadeDrive(GenericHID& stick, bool squaredInputs = true); - void ArcadeDrive(GenericHID* moveStick, uint32_t moveChannel, - GenericHID* rotateStick, uint32_t rotateChannel, + void ArcadeDrive(GenericHID* moveStick, int moveChannel, + GenericHID* rotateStick, int rotateChannel, bool squaredInputs = true); - void ArcadeDrive(GenericHID& moveStick, uint32_t moveChannel, - GenericHID& rotateStick, uint32_t rotateChannel, + void ArcadeDrive(GenericHID& moveStick, int moveChannel, + GenericHID& rotateStick, int rotateChannel, bool squaredInputs = true); void ArcadeDrive(float moveValue, float rotateValue, bool squaredInputs = true); @@ -103,9 +101,9 @@ class RobotDrive : public MotorSafety, public ErrorBase { void Normalize(double* wheelSpeeds); void RotateVector(double& x, double& y, double angle); - static const int32_t kMaxNumberOfMotors = 4; + static const int kMaxNumberOfMotors = 4; - int32_t m_invertedMotors[kMaxNumberOfMotors] = {1, 1, 1, 1}; + int m_invertedMotors[kMaxNumberOfMotors] = {1, 1, 1, 1}; float m_sensitivity = 0.5; double m_maxOutput = 1.0; bool m_deleteSpeedControllers; @@ -116,7 +114,7 @@ class RobotDrive : public MotorSafety, public ErrorBase { // FIXME: MotorSafetyHelper *m_safetyHelper; private: - int32_t GetNumMotors() { + int GetNumMotors() { int motors = 0; if (m_frontLeftMotor) motors++; if (m_frontRightMotor) motors++; diff --git a/wpilibc/sim/include/SafePWM.h b/wpilibc/sim/include/SafePWM.h index 0c09dd5181..70925059cd 100644 --- a/wpilibc/sim/include/SafePWM.h +++ b/wpilibc/sim/include/SafePWM.h @@ -22,7 +22,7 @@ */ class SafePWM : public PWM, public MotorSafety { public: - explicit SafePWM(uint32_t channel); + explicit SafePWM(int channel); virtual ~SafePWM() = default; void SetExpiration(float timeout); diff --git a/wpilibc/sim/include/Solenoid.h b/wpilibc/sim/include/Solenoid.h index e6dc5aa7dd..02f6e8eb77 100644 --- a/wpilibc/sim/include/Solenoid.h +++ b/wpilibc/sim/include/Solenoid.h @@ -22,8 +22,8 @@ */ class Solenoid : public LiveWindowSendable, public ITableListener { public: - explicit Solenoid(uint32_t channel); - Solenoid(uint8_t moduleNumber, uint32_t channel); + explicit Solenoid(int channel); + Solenoid(int moduleNumber, int channel); virtual ~Solenoid(); virtual void Set(bool on); virtual bool Get() const; diff --git a/wpilibc/sim/include/Talon.h b/wpilibc/sim/include/Talon.h index 5e6dc13e89..a27d6dc978 100644 --- a/wpilibc/sim/include/Talon.h +++ b/wpilibc/sim/include/Talon.h @@ -16,7 +16,7 @@ */ class Talon : public SafePWM, public SpeedController { public: - explicit Talon(uint32_t channel); + explicit Talon(int channel); virtual ~Talon() = default; virtual void Set(float value); virtual float Get() const; diff --git a/wpilibc/sim/include/Victor.h b/wpilibc/sim/include/Victor.h index 39b7fc4a9c..6442937106 100644 --- a/wpilibc/sim/include/Victor.h +++ b/wpilibc/sim/include/Victor.h @@ -16,7 +16,7 @@ */ class Victor : public SafePWM, public SpeedController { public: - explicit Victor(uint32_t channel); + explicit Victor(int channel); virtual ~Victor() = default; virtual void Set(float value); virtual float Get() const; diff --git a/wpilibc/sim/include/simulation/MainNode.h b/wpilibc/sim/include/simulation/MainNode.h index 82bb0ac1a8..aecf6b2345 100644 --- a/wpilibc/sim/include/simulation/MainNode.h +++ b/wpilibc/sim/include/simulation/MainNode.h @@ -25,7 +25,7 @@ class MainNode { template static transport::PublisherPtr Advertise(const std::string& topic, - unsigned int _queueLimit = 10, + int _queueLimit = 10, bool _latch = false) { return GetInstance()->main->Advertise(topic, _queueLimit, _latch); } diff --git a/wpilibc/sim/src/AnalogGyro.cpp b/wpilibc/sim/src/AnalogGyro.cpp index 6677f48ad8..1383ec0bb8 100644 --- a/wpilibc/sim/src/AnalogGyro.cpp +++ b/wpilibc/sim/src/AnalogGyro.cpp @@ -13,8 +13,8 @@ #include "Timer.h" #include "WPIErrors.h" -const uint32_t AnalogGyro::kOversampleBits = 10; -const uint32_t AnalogGyro::kAverageBits = 0; +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; @@ -44,7 +44,7 @@ void AnalogGyro::InitAnalogGyro(int channel) { * * @param channel The analog channel the gyro is connected to. */ -AnalogGyro::AnalogGyro(uint32_t channel) { InitAnalogGyro(channel); } +AnalogGyro::AnalogGyro(int channel) { InitAnalogGyro(channel); } /** * Reset the gyro. diff --git a/wpilibc/sim/src/AnalogInput.cpp b/wpilibc/sim/src/AnalogInput.cpp index 08d432fcaa..1afdfb3bf1 100644 --- a/wpilibc/sim/src/AnalogInput.cpp +++ b/wpilibc/sim/src/AnalogInput.cpp @@ -17,7 +17,7 @@ * * @param channel The channel number to represent. */ -AnalogInput::AnalogInput(uint32_t channel) : m_channel(channel) { +AnalogInput::AnalogInput(int channel) : m_channel(channel) { std::stringstream ss; ss << "analog/" << channel; m_impl = new SimFloatInput(ss.str()); @@ -54,7 +54,7 @@ float AnalogInput::GetAverageVoltage() const { return m_impl->Get(); } * * @return The channel number. */ -uint32_t AnalogInput::GetChannel() const { return m_channel; } +int AnalogInput::GetChannel() const { return m_channel; } /** * Get the Average value for the PID Source base object. diff --git a/wpilibc/sim/src/DigitalInput.cpp b/wpilibc/sim/src/DigitalInput.cpp index 5e333d31e2..9b8e830d55 100644 --- a/wpilibc/sim/src/DigitalInput.cpp +++ b/wpilibc/sim/src/DigitalInput.cpp @@ -17,7 +17,7 @@ * * @param channel The digital channel (1..14). */ -DigitalInput::DigitalInput(uint32_t channel) : m_channel(channel) { +DigitalInput::DigitalInput(int channel) : m_channel(channel) { std::stringstream ss; ss << "dio/" << channel; m_impl = new SimDigitalInput(ss.str()); @@ -27,12 +27,12 @@ DigitalInput::DigitalInput(uint32_t channel) : m_channel(channel) { * Get the value from a digital input channel. * Retrieve the value of a single digital input channel from the FPGA. */ -uint32_t DigitalInput::Get() const { return m_impl->Get(); } +int DigitalInput::Get() const { return m_impl->Get(); } /** * @return The GPIO channel number that this object represents. */ -uint32_t DigitalInput::GetChannel() const { return m_channel; } +int DigitalInput::GetChannel() const { return m_channel; } void DigitalInput::UpdateTable() { if (m_table != nullptr) { diff --git a/wpilibc/sim/src/DoubleSolenoid.cpp b/wpilibc/sim/src/DoubleSolenoid.cpp index 4ca0a0d3e7..c5629b81e1 100644 --- a/wpilibc/sim/src/DoubleSolenoid.cpp +++ b/wpilibc/sim/src/DoubleSolenoid.cpp @@ -16,7 +16,7 @@ * @param forwardChannel The forward channel on the module to control. * @param reverseChannel The reverse channel on the module to control. */ -DoubleSolenoid::DoubleSolenoid(uint32_t forwardChannel, uint32_t reverseChannel) +DoubleSolenoid::DoubleSolenoid(int forwardChannel, int reverseChannel) : DoubleSolenoid(1, forwardChannel, reverseChannel) {} /** @@ -26,8 +26,8 @@ DoubleSolenoid::DoubleSolenoid(uint32_t forwardChannel, uint32_t reverseChannel) * @param forwardChannel The forward channel on the module to control. * @param reverseChannel The reverse channel on the module to control. */ -DoubleSolenoid::DoubleSolenoid(uint8_t moduleNumber, uint32_t forwardChannel, - uint32_t reverseChannel) { +DoubleSolenoid::DoubleSolenoid(int moduleNumber, int forwardChannel, + int reverseChannel) { m_reversed = false; if (reverseChannel < forwardChannel) { // Swap ports to get the right address int channel = reverseChannel; diff --git a/wpilibc/sim/src/DriverStation.cpp b/wpilibc/sim/src/DriverStation.cpp index 6cb4a40553..b1aa4515ea 100644 --- a/wpilibc/sim/src/DriverStation.cpp +++ b/wpilibc/sim/src/DriverStation.cpp @@ -17,11 +17,11 @@ #include "WPIErrors.h" #include "simulation/MainNode.h" -const uint32_t DriverStation::kBatteryChannel; -const uint32_t DriverStation::kJoystickPorts; -const uint32_t DriverStation::kJoystickAxes; +const int DriverStation::kBatteryChannel; +const int DriverStation::kJoystickPorts; +const int DriverStation::kJoystickAxes; const float DriverStation::kUpdatePeriod = 0.02; -uint8_t DriverStation::m_updateNumber = 0; +int DriverStation::m_updateNumber = 0; /** * DriverStation contructor. @@ -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(uint32_t stick, uint32_t axis) { +float DriverStation::GetStickAxis(int stick, int axis) { if (axis < 0 || axis > (kJoystickAxes - 1)) { wpi_setWPIError(BadJoystickAxis); return 0.0; @@ -105,7 +105,7 @@ float DriverStation::GetStickAxis(uint32_t stick, uint32_t axis) { * @param button The button number to check. * @return If the button is pressed. */ -bool DriverStation::GetStickButton(uint32_t stick, uint32_t button) { +bool DriverStation::GetStickButton(int stick, int button) { if (stick < 0 || stick >= 6) { wpi_setWPIErrorWithContext(ParameterOutOfRange, "stick must be between 0 and 5"); @@ -128,7 +128,7 @@ bool DriverStation::GetStickButton(uint32_t stick, uint32_t button) { * @param stick The joystick to read. * @return The state of the buttons on the joystick. */ -int16_t DriverStation::GetStickButtons(uint32_t stick) { +int16_t DriverStation::GetStickButtons(int stick) { if (stick < 0 || stick >= 6) { wpi_setWPIErrorWithContext(ParameterOutOfRange, "stick must be between 0 and 5"); @@ -161,7 +161,7 @@ int16_t DriverStation::GetStickButtons(uint32_t stick) { * Valid range is 1 - 4. * @return The analog voltage on the input. */ -float DriverStation::GetAnalogIn(uint32_t channel) { +float DriverStation::GetAnalogIn(int channel) { wpi_setWPIErrorWithContext(UnsupportedInSimulation, "GetAnalogIn"); return 0.0; } @@ -174,7 +174,7 @@ float DriverStation::GetAnalogIn(uint32_t channel) { * * @param channel The digital input to get. Valid range is 1 - 8. */ -bool DriverStation::GetDigitalIn(uint32_t channel) { +bool DriverStation::GetDigitalIn(int channel) { wpi_setWPIErrorWithContext(UnsupportedInSimulation, "GetDigitalIn"); return false; } @@ -188,7 +188,7 @@ bool DriverStation::GetDigitalIn(uint32_t channel) { * @param channel The digital output to set. Valid range is 1 - 8. * @param value The state to set the digital output. */ -void DriverStation::SetDigitalOut(uint32_t channel, bool value) { +void DriverStation::SetDigitalOut(int channel, bool value) { wpi_setWPIErrorWithContext(UnsupportedInSimulation, "SetDigitalOut"); } @@ -198,7 +198,7 @@ void DriverStation::SetDigitalOut(uint32_t channel, bool value) { * @param channel The digital ouput to monitor. Valid range is 1 through 8. * @return A digital value being output on the Drivers Station. */ -bool DriverStation::GetDigitalOut(uint32_t channel) { +bool DriverStation::GetDigitalOut(int channel) { wpi_setWPIErrorWithContext(UnsupportedInSimulation, "GetDigitalOut"); return false; } @@ -253,7 +253,7 @@ DriverStation::Alliance DriverStation::GetAlliance() const { * This could return 1, 2, or 3. * @return The location of the driver station */ -uint32_t DriverStation::GetLocation() const { +int DriverStation::GetLocation() const { return -1; // TODO: Support locations } @@ -304,7 +304,7 @@ void DriverStation::ReportWarning(std::string error) { * Report an error to the DriverStation messages window. * The error is also printed to the program console. */ -void DriverStation::ReportError(bool is_error, int32_t code, +void DriverStation::ReportError(bool is_error, int code, const std::string& error, const std::string& location, const std::string& stack) { diff --git a/wpilibc/sim/src/Encoder.cpp b/wpilibc/sim/src/Encoder.cpp index 0c6792cf53..72ee8c70d3 100644 --- a/wpilibc/sim/src/Encoder.cpp +++ b/wpilibc/sim/src/Encoder.cpp @@ -10,7 +10,6 @@ #include #include "LiveWindow/LiveWindow.h" -#include "Resource.h" #include "WPIErrors.h" /** @@ -30,15 +29,15 @@ * value will either exactly match the spec'd count or * be double (2x) the spec'd count. */ -void Encoder::InitEncoder(int32_t channelA, int32_t channelB, - bool reverseDirection, EncodingType encodingType) { +void Encoder::InitEncoder(int channelA, int channelB, bool reverseDirection, + EncodingType encodingType) { m_table = nullptr; this->channelA = channelA; this->channelB = channelB; m_encodingType = encodingType; m_encodingScale = encodingType == k4X ? 4 : encodingType == k2X ? 2 : 1; - int32_t index = 0; + int index = 0; m_distancePerPulse = 1.0; LiveWindow::GetInstance()->AddSensor("Encoder", channelA, this); @@ -77,7 +76,7 @@ void Encoder::InitEncoder(int32_t channelA, int32_t channelB, * value will either exactly match the spec'd count or * be double (2x) the spec'd count. */ -Encoder::Encoder(uint32_t aChannel, uint32_t bChannel, bool reverseDirection, +Encoder::Encoder(int aChannel, int bChannel, bool reverseDirection, EncodingType encodingType) { InitEncoder(aChannel, bChannel, reverseDirection, encodingType); } @@ -204,7 +203,7 @@ double Encoder::DecodingScaleFactor() const { * * Used to divide raw edge counts down to spec'd counts. */ -int32_t Encoder::GetEncodingScale() const { return m_encodingScale; } +int Encoder::GetEncodingScale() const { return m_encodingScale; } /** * Gets the raw value from the encoder. @@ -214,7 +213,7 @@ int32_t Encoder::GetEncodingScale() const { return m_encodingScale; } * * @return Current raw count from the encoder */ -int32_t Encoder::GetRaw() const { +int Encoder::GetRaw() const { throw "Simulation doesn't currently support this method."; } @@ -227,7 +226,7 @@ int32_t Encoder::GetRaw() const { * @return Current count from the Encoder adjusted for the 1x, 2x, or 4x scale * factor. */ -int32_t Encoder::Get() const { +int Encoder::Get() const { throw "Simulation doesn't currently support this method."; } diff --git a/wpilibc/sim/src/Jaguar.cpp b/wpilibc/sim/src/Jaguar.cpp index d14684529b..bc3cf6397b 100644 --- a/wpilibc/sim/src/Jaguar.cpp +++ b/wpilibc/sim/src/Jaguar.cpp @@ -11,7 +11,7 @@ /** * @param channel The PWM channel that the Jaguar is attached to. */ -Jaguar::Jaguar(uint32_t channel) : SafePWM(channel) { +Jaguar::Jaguar(int channel) : SafePWM(channel) { /* * Input profile defined by Luminary Micro. * diff --git a/wpilibc/sim/src/Joystick.cpp b/wpilibc/sim/src/Joystick.cpp index b878178fd7..bafe62ae67 100644 --- a/wpilibc/sim/src/Joystick.cpp +++ b/wpilibc/sim/src/Joystick.cpp @@ -11,13 +11,13 @@ #include "DriverStation.h" #include "WPIErrors.h" -const uint32_t Joystick::kDefaultXAxis; -const uint32_t Joystick::kDefaultYAxis; -const uint32_t Joystick::kDefaultZAxis; -const uint32_t Joystick::kDefaultTwistAxis; -const uint32_t Joystick::kDefaultThrottleAxis; -const uint32_t Joystick::kDefaultTriggerButton; -const uint32_t Joystick::kDefaultTopButton; +const int Joystick::kDefaultXAxis; +const int Joystick::kDefaultYAxis; +const int Joystick::kDefaultZAxis; +const int Joystick::kDefaultTwistAxis; +const int Joystick::kDefaultThrottleAxis; +const int Joystick::kDefaultTriggerButton; +const int Joystick::kDefaultTopButton; static Joystick* joysticks[DriverStation::kJoystickPorts]; static bool joySticksInitialized = false; @@ -28,8 +28,7 @@ static bool joySticksInitialized = false; * * @param port The port on the driver station that the joystick is plugged into. */ -Joystick::Joystick(uint32_t port) - : Joystick(port, kNumAxisTypes, kNumButtonTypes) { +Joystick::Joystick(int port) : Joystick(port, kNumAxisTypes, kNumButtonTypes) { m_axes[kXAxis] = kDefaultXAxis; m_axes[kYAxis] = kDefaultYAxis; m_axes[kZAxis] = kDefaultZAxis; @@ -51,21 +50,20 @@ Joystick::Joystick(uint32_t port) * @param numAxisTypes The number of axis types in the enum. * @param numButtonTypes The number of button types in the enum. */ -Joystick::Joystick(uint32_t port, uint32_t numAxisTypes, - uint32_t numButtonTypes) +Joystick::Joystick(int port, int numAxisTypes, int numButtonTypes) : m_port(port), m_ds(DriverStation::GetInstance()) { if (!joySticksInitialized) { - for (unsigned i = 0; i < DriverStation::kJoystickPorts; i++) + for (int i = 0; i < DriverStation::kJoystickPorts; i++) joysticks[i] = nullptr; joySticksInitialized = true; } joysticks[m_port] = this; - m_axes = std::make_unique(numAxisTypes); - m_buttons = std::make_unique(numButtonTypes); + m_axes = std::make_unique(numAxisTypes); + m_buttons = std::make_unique(numButtonTypes); } -Joystick* Joystick::GetStickForPort(uint32_t port) { +Joystick* Joystick::GetStickForPort(int port) { Joystick* stick = joysticks[port]; if (stick == nullptr) { stick = new Joystick(port); @@ -121,7 +119,7 @@ float Joystick::GetThrottle() const { * @param axis The axis to read [1-6]. * @return The value of the axis. */ -float Joystick::GetRawAxis(uint32_t axis) const { +float Joystick::GetRawAxis(int axis) const { return m_ds.GetStickAxis(m_port, axis); } @@ -199,7 +197,7 @@ bool Joystick::GetBumper(JoystickHand hand) const { * @param button The button number to be read. * @return The state of the button. */ -bool Joystick::GetRawButton(uint32_t button) const { +bool Joystick::GetRawButton(int button) const { return m_ds.GetStickButton(m_port, button); } @@ -208,7 +206,7 @@ bool Joystick::GetRawButton(uint32_t button) const { * * @return the angle of the POV in degrees, or -1 if the POV is not pressed. */ -int Joystick::GetPOV(uint32_t pov) const { +int Joystick::GetPOV(int pov) const { return 0; // TODO } @@ -237,7 +235,7 @@ bool Joystick::GetButton(ButtonType button) const { * @param axis The axis to look up the channel for. * @return The channel fr the axis. */ -uint32_t Joystick::GetAxisChannel(AxisType axis) { return m_axes[axis]; } +int Joystick::GetAxisChannel(AxisType axis) { return m_axes[axis]; } /** * Set the channel associated with a specified axis. @@ -245,7 +243,7 @@ uint32_t Joystick::GetAxisChannel(AxisType axis) { return m_axes[axis]; } * @param axis The axis to set the channel for. * @param channel The channel to set the axis to. */ -void Joystick::SetAxisChannel(AxisType axis, uint32_t channel) { +void Joystick::SetAxisChannel(AxisType axis, int channel) { m_axes[axis] = channel; } diff --git a/wpilibc/sim/src/Notifier.cpp b/wpilibc/sim/src/Notifier.cpp index 49ea408b69..253706ab89 100644 --- a/wpilibc/sim/src/Notifier.cpp +++ b/wpilibc/sim/src/Notifier.cpp @@ -80,7 +80,7 @@ void Notifier::UpdateAlarm() {} * long as its scheduled time is after the current time. Then the item is * removed or rescheduled (repetitive events) in the queue. */ -void Notifier::ProcessQueue(uint32_t mask, void* params) { +void Notifier::ProcessQueue(int mask, void* params) { Notifier* current; // keep processing events until no more diff --git a/wpilibc/sim/src/PIDController.cpp b/wpilibc/sim/src/PIDController.cpp index 3e9697c839..308468ed2a 100644 --- a/wpilibc/sim/src/PIDController.cpp +++ b/wpilibc/sim/src/PIDController.cpp @@ -81,7 +81,7 @@ PIDController::PIDController(float Kp, float Ki, float Kd, float Kf, m_controlLoop = std::make_unique(&PIDController::Calculate, this); m_controlLoop->StartPeriodic(m_period); - static int32_t instances = 0; + static int instances = 0; instances++; m_toleranceType = kNoTolerance; @@ -483,7 +483,7 @@ void PIDController::SetPercentTolerance(float percent) { * not register as on target for at least the specified bufLength cycles. * @param bufLength Number of previous cycles to average. Defaults to 1. */ -void PIDController::SetToleranceBuffer(unsigned bufLength) { +void PIDController::SetToleranceBuffer(int bufLength) { std::lock_guard lock(m_mutex); m_bufLength = bufLength; diff --git a/wpilibc/sim/src/PWM.cpp b/wpilibc/sim/src/PWM.cpp index 803593d4e1..ef5ba7d37a 100644 --- a/wpilibc/sim/src/PWM.cpp +++ b/wpilibc/sim/src/PWM.cpp @@ -14,8 +14,8 @@ const float PWM::kDefaultPwmPeriod = 5.05; const float PWM::kDefaultPwmCenter = 1.5; -const int32_t PWM::kDefaultPwmStepsDown = 1000; -const int32_t PWM::kPwmDisabled = 0; +const int PWM::kDefaultPwmStepsDown = 1000; +const int PWM::kPwmDisabled = 0; /** * Allocate a PWM given a channel number. @@ -27,7 +27,7 @@ const int32_t PWM::kPwmDisabled = 0; * @param channel The PWM channel number. 0-9 are on-board, 10-19 are on the MXP * port */ -PWM::PWM(uint32_t channel) { +PWM::PWM(int channel) { std::stringstream ss; if (!CheckPWMChannel(channel)) { @@ -73,8 +73,8 @@ void PWM::EnableDeadbandElimination(bool eliminateDeadband) { * @param deadbandMin The low end of the deadband range * @param min The minimum pwm value */ -void PWM::SetBounds(int32_t max, int32_t deadbandMax, int32_t center, - int32_t deadbandMin, int32_t min) { +void PWM::SetBounds(int max, int deadbandMax, int center, int deadbandMin, + int min) { // Nothing to do in simulation. } diff --git a/wpilibc/sim/src/Relay.cpp b/wpilibc/sim/src/Relay.cpp index 5bb7dbef6b..538416d676 100644 --- a/wpilibc/sim/src/Relay.cpp +++ b/wpilibc/sim/src/Relay.cpp @@ -22,7 +22,7 @@ * @param channel The channel number (0-3). * @param direction The direction that the Relay object will control. */ -Relay::Relay(uint32_t channel, Relay::Direction direction) +Relay::Relay(int channel, Relay::Direction direction) : m_channel(channel), m_direction(direction) { std::stringstream ss; if (!SensorBase::CheckRelayChannel(m_channel)) { @@ -138,7 +138,7 @@ Relay::Value Relay::Get() const { } } -uint32_t Relay::GetChannel() const { return m_channel; } +int Relay::GetChannel() const { return m_channel; } /** * Set the expiration time for the Relay object. diff --git a/wpilibc/sim/src/RobotDrive.cpp b/wpilibc/sim/src/RobotDrive.cpp index d93b04d940..c9dd4347de 100644 --- a/wpilibc/sim/src/RobotDrive.cpp +++ b/wpilibc/sim/src/RobotDrive.cpp @@ -16,7 +16,7 @@ #undef max #include -const int32_t RobotDrive::kMaxNumberOfMotors; +const int RobotDrive::kMaxNumberOfMotors; static auto make_shared_nodelete(SpeedController* ptr) { return std::shared_ptr(ptr, NullDeleter()); @@ -52,7 +52,7 @@ void RobotDrive::InitRobotDrive() { * @param leftMotorChannel The PWM channel number that drives the left motor. * @param rightMotorChannel The PWM channel number that drives the right motor. */ -RobotDrive::RobotDrive(uint32_t leftMotorChannel, uint32_t rightMotorChannel) { +RobotDrive::RobotDrive(int leftMotorChannel, int rightMotorChannel) { InitRobotDrive(); m_rearLeftMotor = std::make_shared(leftMotorChannel); m_rearRightMotor = std::make_shared(rightMotorChannel); @@ -72,8 +72,8 @@ RobotDrive::RobotDrive(uint32_t leftMotorChannel, uint32_t rightMotorChannel) { * @param frontRightMotor Front right motor channel number * @param rearRightMotor Rear Right motor channel number */ -RobotDrive::RobotDrive(uint32_t frontLeftMotor, uint32_t rearLeftMotor, - uint32_t frontRightMotor, uint32_t rearRightMotor) { +RobotDrive::RobotDrive(int frontLeftMotor, int rearLeftMotor, + int frontRightMotor, int rearRightMotor) { InitRobotDrive(); m_rearLeftMotor = std::make_shared(rearLeftMotor); m_rearRightMotor = std::make_shared(rearRightMotor); @@ -266,8 +266,8 @@ void RobotDrive::TankDrive(GenericHID& leftStick, GenericHID& rightStick, * @param rightStick The Joystick object to use for the right side of the robot. * @param rightAxis The axis to select on the right side Joystick object. */ -void RobotDrive::TankDrive(GenericHID* leftStick, uint32_t leftAxis, - GenericHID* rightStick, uint32_t rightAxis, +void RobotDrive::TankDrive(GenericHID* leftStick, int leftAxis, + GenericHID* rightStick, int rightAxis, bool squaredInputs) { if (leftStick == nullptr || rightStick == nullptr) { wpi_setWPIError(NullParameter); @@ -277,8 +277,8 @@ void RobotDrive::TankDrive(GenericHID* leftStick, uint32_t leftAxis, squaredInputs); } -void RobotDrive::TankDrive(GenericHID& leftStick, uint32_t leftAxis, - GenericHID& rightStick, uint32_t rightAxis, +void RobotDrive::TankDrive(GenericHID& leftStick, int leftAxis, + GenericHID& rightStick, int rightAxis, bool squaredInputs) { TankDrive(leftStick.GetRawAxis(leftAxis), rightStick.GetRawAxis(rightAxis), squaredInputs); @@ -371,8 +371,8 @@ void RobotDrive::ArcadeDrive(GenericHID& stick, bool squaredInputs) { * @param squaredInputs Setting this parameter to true increases the sensitivity * at lower speeds */ -void RobotDrive::ArcadeDrive(GenericHID* moveStick, uint32_t moveAxis, - GenericHID* rotateStick, uint32_t rotateAxis, +void RobotDrive::ArcadeDrive(GenericHID* moveStick, int moveAxis, + GenericHID* rotateStick, int rotateAxis, bool squaredInputs) { float moveValue = moveStick->GetRawAxis(moveAxis); float rotateValue = rotateStick->GetRawAxis(rotateAxis); @@ -396,8 +396,8 @@ void RobotDrive::ArcadeDrive(GenericHID* moveStick, uint32_t moveAxis, * @param squaredInputs Setting this parameter to true increases the sensitivity * at lower speeds */ -void RobotDrive::ArcadeDrive(GenericHID& moveStick, uint32_t moveAxis, - GenericHID& rotateStick, uint32_t rotateAxis, +void RobotDrive::ArcadeDrive(GenericHID& moveStick, int moveAxis, + GenericHID& rotateStick, int rotateAxis, bool squaredInputs) { float moveValue = moveStick.GetRawAxis(moveAxis); float rotateValue = rotateStick.GetRawAxis(rotateAxis); @@ -630,7 +630,7 @@ float RobotDrive::Limit(float num) { */ void RobotDrive::Normalize(double* wheelSpeeds) { double maxMagnitude = fabs(wheelSpeeds[0]); - int32_t i; + int i; for (i = 1; i < kMaxNumberOfMotors; i++) { double temp = fabs(wheelSpeeds[i]); if (maxMagnitude < temp) maxMagnitude = temp; diff --git a/wpilibc/sim/src/SafePWM.cpp b/wpilibc/sim/src/SafePWM.cpp index dd3314b151..c60d362d7b 100644 --- a/wpilibc/sim/src/SafePWM.cpp +++ b/wpilibc/sim/src/SafePWM.cpp @@ -14,7 +14,7 @@ * * @param channel The PWM channel number (0..19). */ -SafePWM::SafePWM(uint32_t channel) : PWM(channel) { +SafePWM::SafePWM(int channel) : PWM(channel) { m_safetyHelper = std::make_unique(this); m_safetyHelper->SetSafetyEnabled(false); } diff --git a/wpilibc/sim/src/SampleRobot.cpp b/wpilibc/sim/src/SampleRobot.cpp index d01ec69778..d02da8cf63 100644 --- a/wpilibc/sim/src/SampleRobot.cpp +++ b/wpilibc/sim/src/SampleRobot.cpp @@ -18,7 +18,7 @@ #include #elif defined(_WIN32) #include -void sleep(unsigned milliseconds) { Sleep(milliseconds); } +void sleep(unsigned int milliseconds) { Sleep(milliseconds); } #endif SampleRobot::SampleRobot() : m_robotMainOverridden(true) {} diff --git a/wpilibc/sim/src/Solenoid.cpp b/wpilibc/sim/src/Solenoid.cpp index f2d658f48b..e18cc2d8eb 100644 --- a/wpilibc/sim/src/Solenoid.cpp +++ b/wpilibc/sim/src/Solenoid.cpp @@ -18,7 +18,7 @@ * * @param channel The channel on the solenoid module to control (1..8). */ -Solenoid::Solenoid(uint32_t channel) : Solenoid(1, channel) {} +Solenoid::Solenoid(int channel) : Solenoid(1, channel) {} /** * Constructor. @@ -26,7 +26,7 @@ Solenoid::Solenoid(uint32_t channel) : Solenoid(1, channel) {} * @param moduleNumber The solenoid module (1 or 2). * @param channel The channel on the solenoid module to control (1..8). */ -Solenoid::Solenoid(uint8_t moduleNumber, uint32_t channel) { +Solenoid::Solenoid(int moduleNumber, int channel) { std::stringstream ss; ss << "pneumatic/" << moduleNumber << "/" << channel; m_impl = new SimContinuousOutput(ss.str()); diff --git a/wpilibc/sim/src/Talon.cpp b/wpilibc/sim/src/Talon.cpp index e25976f24b..9a63b897af 100644 --- a/wpilibc/sim/src/Talon.cpp +++ b/wpilibc/sim/src/Talon.cpp @@ -12,7 +12,7 @@ /** * @param channel The PWM channel that the Talon is attached to. */ -Talon::Talon(uint32_t channel) : SafePWM(channel) { +Talon::Talon(int channel) : SafePWM(channel) { /* Note that the Talon uses the following bounds for PWM values. These values * should work reasonably well for most controllers, but if users experience * issues such as asymmetric behavior around the deadband or inability to diff --git a/wpilibc/sim/src/Utility.cpp b/wpilibc/sim/src/Utility.cpp index db1dc106b1..fd3296e507 100644 --- a/wpilibc/sim/src/Utility.cpp +++ b/wpilibc/sim/src/Utility.cpp @@ -53,8 +53,8 @@ static void wpi_handleTracing() { * Utility.h. */ bool wpi_assert_impl(bool conditionValue, const char* conditionText, - const char* message, const char* fileName, - uint32_t lineNumber, const char* funcName) { + const char* message, const char* fileName, int lineNumber, + const char* funcName) { if (!conditionValue) { std::stringstream errorStream; @@ -84,8 +84,7 @@ bool wpi_assert_impl(bool conditionValue, const char* conditionText, void wpi_assertEqual_common_impl(int valueA, int valueB, const std::string& equalityType, const std::string& message, - const std::string& fileName, - uint32_t lineNumber, + const std::string& fileName, int lineNumber, const std::string& funcName) { // Error string buffer std::stringstream error; @@ -116,7 +115,7 @@ void wpi_assertEqual_common_impl(int valueA, int valueB, * Utility.h. */ bool wpi_assertEqual_impl(int valueA, int valueB, const std::string& message, - const std::string& fileName, uint32_t lineNumber, + const std::string& fileName, int lineNumber, const std::string& funcName) { if (!(valueA == valueB)) { wpi_assertEqual_common_impl(valueA, valueB, "!=", message, fileName, @@ -133,7 +132,7 @@ bool wpi_assertEqual_impl(int valueA, int valueB, const std::string& message, * Utility.h. */ bool wpi_assertNotEqual_impl(int valueA, int valueB, const std::string& message, - const std::string& fileName, uint32_t lineNumber, + const std::string& fileName, int lineNumber, const std::string& funcName) { if (!(valueA != valueB)) { wpi_assertEqual_common_impl(valueA, valueB, "==", message, fileName, @@ -159,7 +158,7 @@ uint64_t GetFPGATime() { return wpilib::internal::simTime * 1e6; } static std::string demangle(char const* mangledSymbol) { char buffer[256]; size_t length; - int status; + int32_t status; if (sscanf(mangledSymbol, "%*[^(]%*[^_]%255[^)+]", buffer)) { char* symbol = abi::__cxa_demangle(buffer, nullptr, &length, &status); @@ -180,7 +179,7 @@ static std::string demangle(char const* mangledSymbol) { /** * Get a stack trace, ignoring the first "offset" symbols. */ -std::string GetStackTrace(uint32_t offset) { +std::string GetStackTrace(int offset) { void* stackTrace[128]; int stackSize = backtrace(stackTrace, 128); char** mangledSymbols = backtrace_symbols(stackTrace, stackSize); @@ -202,7 +201,5 @@ std::string GetStackTrace(uint32_t offset) { static std::string demangle(char const* mangledSymbol) { return "no demangling on windows"; } -std::string GetStackTrace(uint32_t offset) { - return "no stack trace on windows"; -} +std::string GetStackTrace(int offset) { return "no stack trace on windows"; } #endif diff --git a/wpilibc/sim/src/Victor.cpp b/wpilibc/sim/src/Victor.cpp index 815dd6a05f..2b22a8ec52 100644 --- a/wpilibc/sim/src/Victor.cpp +++ b/wpilibc/sim/src/Victor.cpp @@ -12,7 +12,7 @@ /** * @param channel The PWM channel that the Victor is attached to. */ -Victor::Victor(uint32_t channel) : SafePWM(channel) { +Victor::Victor(int channel) : SafePWM(channel) { /* Note that the Victor uses the following bounds for PWM values. These values * were determined empirically and optimized for the Victor 888. These values * should work reasonably well for Victor 884 controllers as well but if users diff --git a/wpilibcIntegrationTests/include/TestBench.h b/wpilibcIntegrationTests/include/TestBench.h index aa875407f6..a941b45d2a 100644 --- a/wpilibcIntegrationTests/include/TestBench.h +++ b/wpilibcIntegrationTests/include/TestBench.h @@ -71,6 +71,6 @@ class TestBench { static constexpr double kSinglePoleIIRExpectedOutput = -3.2172003; static constexpr double kHighPassTimeConstant = 0.006631; static constexpr double kHighPassExpectedOutput = 10.074717; - static constexpr int kMovAvgTaps = 6; + static constexpr int32_t kMovAvgTaps = 6; static constexpr double kMovAvgExpectedOutput = -10.191644; }; diff --git a/wpilibcIntegrationTests/include/command/MockCommand.h b/wpilibcIntegrationTests/include/command/MockCommand.h index 421d5eb7b1..31cf0bc3ae 100644 --- a/wpilibcIntegrationTests/include/command/MockCommand.h +++ b/wpilibcIntegrationTests/include/command/MockCommand.h @@ -11,12 +11,12 @@ class MockCommand : public Command { private: - int m_initializeCount; - int m_executeCount; - int m_isFinishedCount; + int32_t m_initializeCount; + int32_t m_executeCount; + int32_t m_isFinishedCount; bool m_hasFinished; - int m_endCount; - int m_interruptedCount; + int32_t m_endCount; + int32_t m_interruptedCount; protected: virtual void Initialize(); @@ -27,16 +27,16 @@ class MockCommand : public Command { public: MockCommand(); - int GetInitializeCount() { return m_initializeCount; } + int32_t GetInitializeCount() { return m_initializeCount; } bool HasInitialized(); - int GetExecuteCount() { return m_executeCount; } - int GetIsFinishedCount() { return m_isFinishedCount; } + int32_t GetExecuteCount() { return m_executeCount; } + int32_t GetIsFinishedCount() { return m_isFinishedCount; } bool IsHasFinished() { return m_hasFinished; } void SetHasFinished(bool hasFinished) { m_hasFinished = hasFinished; } - int GetEndCount() { return m_endCount; } + int32_t GetEndCount() { return m_endCount; } bool HasEnd(); - int GetInterruptedCount() { return m_interruptedCount; } + int32_t GetInterruptedCount() { return m_interruptedCount; } bool HasInterrupted(); }; diff --git a/wpilibcIntegrationTests/src/AnalogLoopTest.cpp b/wpilibcIntegrationTests/src/AnalogLoopTest.cpp index 260919bec2..ae200b7ba9 100644 --- a/wpilibcIntegrationTests/src/AnalogLoopTest.cpp +++ b/wpilibcIntegrationTests/src/AnalogLoopTest.cpp @@ -40,7 +40,7 @@ class AnalogLoopTest : public testing::Test { */ TEST_F(AnalogLoopTest, AnalogInputWorks) { // Set the output voltage and check if the input measures the same voltage - for (int i = 0; i < 50; i++) { + for (int32_t i = 0; i < 50; i++) { m_output->SetVoltage(i / 10.0f); Wait(kDelayTime); @@ -90,7 +90,7 @@ TEST_F(AnalogLoopTest, AnalogTriggerCounterWorks) { Counter counter(trigger); // Turn the analog output low and high 50 times - for (int i = 0; i < 50; i++) { + for (int32_t i = 0; i < 50; i++) { m_output->SetVoltage(1.0); Wait(kDelayTime); m_output->SetVoltage(4.0); @@ -103,15 +103,15 @@ TEST_F(AnalogLoopTest, AnalogTriggerCounterWorks) { } static void InterruptHandler(uint32_t interruptAssertedMask, void* param) { - *reinterpret_cast(param) = 12345; + *reinterpret_cast(param) = 12345; } TEST_F(AnalogLoopTest, AsynchronusInterruptWorks) { - int param = 0; + int32_t param = 0; AnalogTrigger trigger(m_input); trigger.SetLimitsVoltage(2.0f, 3.0f); - // Given an interrupt handler that sets an int to 12345 + // Given an interrupt handler that sets an int32_t to 12345 std::shared_ptr triggerOutput = trigger.CreateOutput(AnalogTriggerType::kState); triggerOutput->RequestInterrupts(InterruptHandler, ¶m); @@ -123,7 +123,7 @@ TEST_F(AnalogLoopTest, AsynchronusInterruptWorks) { m_output->SetVoltage(5.0); triggerOutput->CancelInterrupts(); - // Then the int should be 12345 + // Then the int32_t should be 12345 Wait(kDelayTime); EXPECT_EQ(12345, param) << "The interrupt did not run."; } diff --git a/wpilibcIntegrationTests/src/CANJaguarTest.cpp b/wpilibcIntegrationTests/src/CANJaguarTest.cpp index 9b54b51f10..4e6bc70c8e 100644 --- a/wpilibcIntegrationTests/src/CANJaguarTest.cpp +++ b/wpilibcIntegrationTests/src/CANJaguarTest.cpp @@ -79,7 +79,7 @@ class CANJaguarTest : public testing::Test { * called in each iteration of the main loop. */ void SetJaguar(float totalTime, float value = 0.0f) { - for (int i = 0; i < 50; i++) { + for (int32_t i = 0; i < 50; i++) { m_jaguar->Set(value); Wait(totalTime / 50.0); } @@ -87,7 +87,7 @@ class CANJaguarTest : public testing::Test { /** * returns the sign of the given number */ - int SignNum(double value) { return -(value < 0) + (value > 0); } + int32_t SignNum(double value) { return -(value < 0) + (value > 0); } void InversionTest(float motorValue, float delayTime = kMotorTime) { m_jaguar->EnableControl(); m_jaguar->SetInverted(false); @@ -218,7 +218,7 @@ TEST_F(CANJaguarTest, BrownOut) { /* The jaguar should automatically get set to quad encoder position mode, so it should be able to reach a setpoint in a couple seconds. */ - for (int i = 0; i < 10; i++) { + for (int32_t i = 0; i < 10; i++) { SetJaguar(1.0f, setpoint); if (std::abs(m_jaguar->GetPosition() - setpoint) <= @@ -333,7 +333,7 @@ TEST_F(CANJaguarTest, PositionModeWorks) { m_jaguar->EnableControl(); /* It should get to the setpoint within 10 seconds */ - for (int i = 0; i < 10; i++) { + for (int32_t i = 0; i < 10; i++) { SetJaguar(1.0f, setpoint); if (std::abs(m_jaguar->GetPosition() - setpoint) <= @@ -361,7 +361,7 @@ TEST_F(CANJaguarTest, DISABLED_CurrentModeWorks) { float expectedCurrent = std::abs(setpoints_i); /* It should get to each setpoint within 10 seconds */ - for (int j = 0; j < 10; j++) { + for (int32_t j = 0; j < 10; j++) { SetJaguar(1.0, setpoint); if (std::abs(m_jaguar->GetOutputCurrent() - expectedCurrent) <= @@ -385,7 +385,7 @@ TEST_F(CANJaguarTest, FakePotentiometerPosition) { // Set the analog output to 4 different voltages and check if the Jaguar // returns corresponding positions. - for (int i = 0; i <= 3; i++) { + for (int32_t i = 0; i <= 3; i++) { m_fakePotentiometer->SetVoltage(static_cast(i)); SetJaguar(kPotentiometerSettlingTime); diff --git a/wpilibcIntegrationTests/src/CANTalonTest.cpp b/wpilibcIntegrationTests/src/CANTalonTest.cpp index 4f8c46c1a6..b11956d05d 100644 --- a/wpilibcIntegrationTests/src/CANTalonTest.cpp +++ b/wpilibcIntegrationTests/src/CANTalonTest.cpp @@ -11,7 +11,7 @@ #include "Timer.h" #include "gtest/gtest.h" -const int deviceId = 0; +const int32_t deviceId = 0; TEST(CANTalonTest, QuickTest) { double throttle = 0.1; diff --git a/wpilibcIntegrationTests/src/DIOLoopTest.cpp b/wpilibcIntegrationTests/src/DIOLoopTest.cpp index 81d3bbd334..d6864043e8 100644 --- a/wpilibcIntegrationTests/src/DIOLoopTest.cpp +++ b/wpilibcIntegrationTests/src/DIOLoopTest.cpp @@ -128,7 +128,7 @@ TEST_F(DIOLoopTest, FakeCounter) { EXPECT_EQ(0, counter.Get()) << "Counter did not initialize to 0."; /* Count 100 ticks. The counter value should be 100 after this loop. */ - for (int i = 0; i < 100; i++) { + for (int32_t i = 0; i < 100; i++) { m_output->Set(true); Wait(kCounterTime); m_output->Set(false); @@ -139,13 +139,13 @@ TEST_F(DIOLoopTest, FakeCounter) { } static void InterruptHandler(uint32_t interruptAssertedMask, void* param) { - *reinterpret_cast(param) = 12345; + *reinterpret_cast(param) = 12345; } TEST_F(DIOLoopTest, AsynchronousInterruptWorks) { - int param = 0; + int32_t param = 0; - // Given an interrupt handler that sets an int to 12345 + // Given an interrupt handler that sets an int32_t to 12345 m_input->RequestInterrupts(InterruptHandler, ¶m); m_input->EnableInterrupts(); @@ -154,7 +154,7 @@ TEST_F(DIOLoopTest, AsynchronousInterruptWorks) { m_output->Set(true); m_input->CancelInterrupts(); - // Then the int should be 12345 + // Then the int32_t should be 12345 Wait(kDelayTime); EXPECT_EQ(12345, param) << "The interrupt did not run."; } diff --git a/wpilibcIntegrationTests/src/FakeEncoderTest.cpp b/wpilibcIntegrationTests/src/FakeEncoderTest.cpp index b09d20908e..4c33d45cbe 100644 --- a/wpilibcIntegrationTests/src/FakeEncoderTest.cpp +++ b/wpilibcIntegrationTests/src/FakeEncoderTest.cpp @@ -54,7 +54,7 @@ class FakeEncoderTest : public testing::Test { * ticks */ void Simulate100QuadratureTicks() { - for (int i = 0; i < 100; i++) { + for (int32_t i = 0; i < 100; i++) { m_outputA->Set(true); Wait(kDelayTime); m_outputB->Set(true); diff --git a/wpilibcIntegrationTests/src/MutexTest.cpp b/wpilibcIntegrationTests/src/MutexTest.cpp index 6e7266747a..5c8c4ceaac 100644 --- a/wpilibcIntegrationTests/src/MutexTest.cpp +++ b/wpilibcIntegrationTests/src/MutexTest.cpp @@ -46,7 +46,7 @@ class Notification { bool m_set = false; }; -void SetProcessorAffinity(int core_id) { +void SetProcessorAffinity(int32_t core_id) { cpu_set_t cpuset; CPU_ZERO(&cpuset); CPU_SET(core_id, &cpuset); @@ -56,7 +56,7 @@ void SetProcessorAffinity(int core_id) { 0); } -void SetThreadRealtimePriorityOrDie(int priority) { +void SetThreadRealtimePriorityOrDie(int32_t priority) { struct sched_param param; // Set realtime priority for this thread param.sched_priority = priority + sched_get_priority_min(SCHED_RR); diff --git a/wpilibcIntegrationTests/src/TiltPanCameraTest.cpp b/wpilibcIntegrationTests/src/TiltPanCameraTest.cpp index e5c32f3bed..070618b007 100644 --- a/wpilibcIntegrationTests/src/TiltPanCameraTest.cpp +++ b/wpilibcIntegrationTests/src/TiltPanCameraTest.cpp @@ -86,7 +86,7 @@ void TiltPanCameraTest::GyroAngle() { Wait(0.5); m_gyro->Reset(); - for (int i = 0; i < 600; i++) { + for (int32_t i = 0; i < 600; i++) { m_pan->Set(i / 1000.0); Wait(0.001); } @@ -122,7 +122,7 @@ void TiltPanCameraTest::GyroCalibratedParameters() { Wait(0.5); m_gyro->Reset(); - for (int i = 0; i < 600; i++) { + for (int32_t i = 0; i < 600; i++) { m_pan->Set(i / 1000.0); Wait(0.001); } diff --git a/wpilibcIntegrationTests/src/command/CommandTest.cpp b/wpilibcIntegrationTests/src/command/CommandTest.cpp index 965fc2176d..f9af67929f 100644 --- a/wpilibcIntegrationTests/src/command/CommandTest.cpp +++ b/wpilibcIntegrationTests/src/command/CommandTest.cpp @@ -32,8 +32,9 @@ class CommandTest : public testing::Test { */ void TeardownScheduler() { Scheduler::GetInstance()->ResetAll(); } - void AssertCommandState(MockCommand& command, int initialize, int execute, - int isFinished, int end, int interrupted) { + void AssertCommandState(MockCommand& command, int32_t initialize, + int32_t execute, int32_t isFinished, int32_t end, + int32_t interrupted) { EXPECT_EQ(initialize, command.GetInitializeCount()); EXPECT_EQ(execute, command.GetExecuteCount()); EXPECT_EQ(isFinished, command.GetIsFinishedCount()); diff --git a/wpilibj/src/athena/cpp/lib/CANJNI.cpp b/wpilibj/src/athena/cpp/lib/CANJNI.cpp index dbd01222c8..dd374f95cd 100644 --- a/wpilibj/src/athena/cpp/lib/CANJNI.cpp +++ b/wpilibj/src/athena/cpp/lib/CANJNI.cpp @@ -48,7 +48,7 @@ Java_edu_wpi_first_wpilibj_can_CANJNI_FRCNetCommCANSessionMuxSendMessage( if (dataBuffer) { std::ostringstream str; str << std::setfill('0') << std::hex; - for (int i = 0; i < dataSize; i++) { + for (int32_t i = 0; i < dataSize; i++) { str << std::setw(2) << (int)dataBuffer[i] << ' '; } @@ -96,7 +96,7 @@ Java_edu_wpi_first_wpilibj_can_CANJNI_FRCNetCommCANSessionMuxReceiveMessage( if (logDEBUG <= canJNILogLevel) { std::ostringstream str; str << std::setfill('0') << std::hex; - for (int i = 0; i < dataSize; i++) { + for (int32_t i = 0; i < dataSize; i++) { str << std::setw(2) << (int)buffer[i] << ' '; } diff --git a/wpilibj/src/athena/cpp/lib/HALUtil.cpp b/wpilibj/src/athena/cpp/lib/HALUtil.cpp index 059f25b7af..877659572b 100644 --- a/wpilibj/src/athena/cpp/lib/HALUtil.cpp +++ b/wpilibj/src/athena/cpp/lib/HALUtil.cpp @@ -166,7 +166,7 @@ void ReportError(JNIEnv *env, int32_t status, int32_t minRange, int32_t maxRange } } -void ReportCANError(JNIEnv *env, int32_t status, int message_id) { +void ReportCANError(JNIEnv *env, int32_t status, int32_t message_id) { if (status >= 0) return; switch (status) { case kRioStatusSuccess: diff --git a/wpilibj/src/athena/cpp/lib/HALUtil.h b/wpilibj/src/athena/cpp/lib/HALUtil.h index b6447c19ed..75524fed3d 100644 --- a/wpilibj/src/athena/cpp/lib/HALUtil.h +++ b/wpilibj/src/athena/cpp/lib/HALUtil.h @@ -30,9 +30,9 @@ inline bool CheckStatusRange(JNIEnv *env, int32_t status, int32_t minRange, return status == 0; } -void ReportCANError(JNIEnv *env, int32_t status, int message_id); +void ReportCANError(JNIEnv *env, int32_t status, int32_t message_id); -inline bool CheckCANStatus(JNIEnv *env, int32_t status, int message_id) { +inline bool CheckCANStatus(JNIEnv *env, int32_t status, int32_t message_id) { if (status != 0) ReportCANError(env, status, message_id); return status == 0; } diff --git a/wpilibj/src/athena/cpp/lib/InterruptJNI.cpp b/wpilibj/src/athena/cpp/lib/InterruptJNI.cpp index 84b6afa8fc..30e8a07651 100644 --- a/wpilibj/src/athena/cpp/lib/InterruptJNI.cpp +++ b/wpilibj/src/athena/cpp/lib/InterruptJNI.cpp @@ -162,7 +162,7 @@ Java_edu_wpi_first_wpilibj_hal_InterruptJNI_cleanInterrupts( * Method: waitForInterrupt * Signature: (JD)V */ -JNIEXPORT int JNICALL +JNIEXPORT int32_t JNICALL Java_edu_wpi_first_wpilibj_hal_InterruptJNI_waitForInterrupt( JNIEnv* env, jclass, jint interruptHandle, jdouble timeout, jboolean ignorePrevious) { @@ -170,8 +170,8 @@ Java_edu_wpi_first_wpilibj_hal_InterruptJNI_waitForInterrupt( INTERRUPTJNI_LOG(logDEBUG) << "Interrupt Handle = " << (HAL_InterruptHandle)interruptHandle; int32_t status = 0; - int result = HAL_WaitForInterrupt((HAL_InterruptHandle)interruptHandle, timeout, - ignorePrevious, &status); + int32_t result = HAL_WaitForInterrupt((HAL_InterruptHandle)interruptHandle, + timeout, ignorePrevious, &status); INTERRUPTJNI_LOG(logDEBUG) << "Status = " << status; diff --git a/wpilibj/src/athena/cpp/lib/PowerJNI.cpp b/wpilibj/src/athena/cpp/lib/PowerJNI.cpp index 6d3b342c90..2d29a07991 100644 --- a/wpilibj/src/athena/cpp/lib/PowerJNI.cpp +++ b/wpilibj/src/athena/cpp/lib/PowerJNI.cpp @@ -86,7 +86,7 @@ JNIEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_PowerJNI_getUserCurrentFaults6V( JNIEnv* env, jclass) { int32_t status = 0; - int val = HAL_GetUserCurrentFaults6V(&status); + int32_t val = HAL_GetUserCurrentFaults6V(&status); CheckStatus(env, status); return val; } @@ -139,7 +139,7 @@ JNIEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_PowerJNI_getUserCurrentFaults5V( JNIEnv* env, jclass) { int32_t status = 0; - int val = HAL_GetUserCurrentFaults5V(&status); + int32_t val = HAL_GetUserCurrentFaults5V(&status); CheckStatus(env, status); return val; } @@ -192,7 +192,7 @@ JNIEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_PowerJNI_getUserCurrentFaults3V3( JNIEnv* env, jclass) { int32_t status = 0; - int val = HAL_GetUserCurrentFaults3V3(&status); + int32_t val = HAL_GetUserCurrentFaults3V3(&status); CheckStatus(env, status); return val; }