From 0cb288ffba090aa965e264e18650545a342e5a22 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Sun, 10 Jul 2016 17:47:44 -0700 Subject: [PATCH] Fixes warnings thrown by cpplint.py (#154) * Fixed cpplint.py [runtime/int] warnings * Fixed cpplint.py [readability/casting] warnings * Fixed cpplint.py [readability/namespace] warnings * Fixed cpplint.py [readability/braces] warnings * Fixed cpplint.py [whitespace/braces] warnings * Fixed cpplint.py [runtime/explicit] warnings * Fixed cpplint.py [runtime/printf] warnings * Fixed cpplint.py [readability/inheritance] warnings * Fixed cpplint.py [whitespace/tab] warnings * Fixed cpplint.py [build/storage_class] warnings * Fixed cpplint.py [readability/multiline_comment] warnings * Fixed cpplint.py [whitespace/semicolon] warnings * Fixed cpplint.py [readability/check] warnings * Fixed cpplint.py [runtime/arrays] warnings * Ran format.py --- hal/include/HAL/DIO.h | 2 +- hal/lib/athena/AnalogGyro.cpp | 18 ++-- hal/lib/athena/AnalogInput.cpp | 10 +- hal/lib/athena/AnalogInternal.cpp | 2 +- hal/lib/athena/AnalogInternal.h | 8 +- hal/lib/athena/Counter.cpp | 3 +- hal/lib/athena/DIO.cpp | 8 +- hal/lib/athena/DigitalInternal.cpp | 2 +- hal/lib/athena/DigitalInternal.h | 2 +- hal/lib/athena/EncoderInternal.h | 2 +- hal/lib/athena/FPGAEncoder.cpp | 3 +- hal/lib/athena/HALAthena.cpp | 6 +- hal/lib/athena/I2C.cpp | 10 +- hal/lib/athena/Interrupts.cpp | 4 +- hal/lib/athena/PWM.cpp | 32 ++++--- hal/lib/athena/PortsInternal.h | 2 +- hal/lib/athena/Power.cpp | 9 +- hal/lib/athena/SPI.cpp | 24 +++-- hal/lib/athena/SerialPort.cpp | 7 +- .../athena/handles/DigitalHandleResource.h | 2 +- hal/lib/athena/handles/HandlesInternal.cpp | 2 +- hal/lib/athena/handles/HandlesInternal.h | 2 +- .../athena/handles/IndexedHandleResource.h | 2 +- .../handles/LimitedClassedHandleResource.h | 2 +- .../athena/handles/LimitedHandleResource.h | 2 +- .../athena/handles/UnlimitedHandleResource.h | 2 +- hal/lib/shared/HAL.cpp | 18 ++-- .../limit_switch/src/external_limit_switch.h | 2 +- wpilibc/athena/include/ADXL345_I2C.h | 20 ++-- wpilibc/athena/include/ADXL345_SPI.h | 22 ++--- wpilibc/athena/include/ADXL362.h | 24 ++--- wpilibc/athena/include/AnalogPotentiometer.h | 16 ++-- wpilibc/athena/include/AnalogTriggerOutput.h | 8 +- wpilibc/athena/include/AnalogTriggerType.h | 2 +- wpilibc/athena/include/BuiltInAccelerometer.h | 22 ++--- wpilibc/athena/include/CANJaguar.h | 72 +++++++------- wpilibc/athena/include/CANTalon.h | 94 +++++++++---------- wpilibc/athena/include/Counter.h | 2 +- wpilibc/athena/include/DigitalInput.h | 6 +- wpilibc/athena/include/DigitalOutput.h | 10 +- wpilibc/athena/include/GearTooth.h | 10 +- wpilibc/athena/include/Joystick.h | 20 ++-- wpilibc/athena/include/MotorSafetyHelper.h | 2 +- wpilibc/athena/include/PWM.h | 4 +- wpilibc/athena/include/PWMSpeedController.h | 14 +-- .../athena/include/PowerDistributionPanel.h | 2 +- wpilibc/athena/include/Relay.h | 2 +- wpilibc/athena/include/SPI.h | 2 +- wpilibc/athena/include/SolenoidBase.h | 4 +- wpilibc/athena/include/Vision/ColorImage.h | 2 +- wpilibc/athena/include/Vision/HSLImage.h | 2 +- wpilibc/athena/include/Vision/ImageBase.h | 2 +- wpilibc/athena/include/Vision/RGBImage.h | 2 +- wpilibc/athena/src/ADXL345_I2C.cpp | 7 +- wpilibc/athena/src/ADXRS450_Gyro.cpp | 7 +- wpilibc/athena/src/CANJaguar.cpp | 80 ++++++++-------- wpilibc/athena/src/CANTalon.cpp | 72 +++++++------- wpilibc/athena/src/CameraServer.cpp | 10 +- wpilibc/athena/src/DriverStation.cpp | 4 +- wpilibc/athena/src/Encoder.cpp | 1 - wpilibc/athena/src/PIDController.cpp | 4 +- wpilibc/athena/src/PWM.cpp | 6 +- wpilibc/athena/src/SPI.cpp | 39 ++++---- wpilibc/athena/src/Servo.cpp | 6 +- wpilibc/athena/src/USBCamera.cpp | 8 +- wpilibc/athena/src/Vision/AxisCamera.cpp | 7 +- wpilibc/athena/src/Vision/BaeUtilities.cpp | 22 ++--- wpilibc/athena/src/Vision/BinaryImage.cpp | 4 +- wpilibc/athena/src/Vision/VisionAPI.cpp | 19 ++-- .../shared/include/Buttons/InternalButton.h | 2 +- wpilibc/shared/include/Buttons/Trigger.h | 6 +- wpilibc/shared/include/CircularBuffer.h | 2 +- wpilibc/shared/include/Commands/Command.h | 16 ++-- .../shared/include/Commands/CommandGroup.h | 2 +- wpilibc/shared/include/Commands/PIDCommand.h | 4 +- .../shared/include/Commands/PIDSubsystem.h | 4 +- .../shared/include/Commands/PrintCommand.h | 2 +- .../shared/include/Commands/StartCommand.h | 2 +- wpilibc/shared/include/Commands/Subsystem.h | 10 +- wpilibc/shared/include/Commands/WaitCommand.h | 2 +- .../shared/include/Commands/WaitForChildren.h | 2 +- .../include/Commands/WaitUntilCommand.h | 2 +- wpilibc/shared/include/Filters/Filter.h | 6 +- wpilibc/shared/include/PIDController.h | 37 ++++---- .../include/SmartDashboard/SendableChooser.h | 6 +- .../shared/include/interfaces/Potentiometer.h | 2 +- wpilibc/shared/src/Buttons/Trigger.cpp | 14 ++- wpilibc/shared/src/Commands/Command.cpp | 4 +- wpilibc/shared/src/Commands/PIDCommand.cpp | 7 +- wpilibc/shared/src/Commands/PIDSubsystem.cpp | 7 +- wpilibc/shared/src/Commands/Scheduler.cpp | 2 +- wpilibc/shared/src/Commands/Subsystem.cpp | 4 +- wpilibc/sim/include/AnalogPotentiometer.h | 17 ++-- wpilibc/sim/include/Counter.h | 2 +- wpilibc/sim/include/DriverStation.h | 2 +- wpilibc/sim/include/Jaguar.h | 2 +- wpilibc/sim/include/Joystick.h | 20 ++-- wpilibc/sim/include/MotorSafetyHelper.h | 2 +- wpilibc/sim/include/PWM.h | 2 +- wpilibc/sim/include/Relay.h | 2 +- wpilibc/sim/include/Talon.h | 2 +- wpilibc/sim/include/Victor.h | 2 +- .../include/simulation/SimContinuousOutput.h | 2 +- .../sim/include/simulation/SimDigitalInput.h | 2 +- wpilibc/sim/include/simulation/SimEncoder.h | 2 +- .../sim/include/simulation/SimFloatInput.h | 2 +- wpilibc/sim/include/simulation/SimGyro.h | 2 +- wpilibc/sim/src/AnalogGyro.cpp | 8 +- wpilibc/sim/src/AnalogInput.cpp | 11 +-- wpilibc/sim/src/DigitalInput.cpp | 11 +-- wpilibc/sim/src/DoubleSolenoid.cpp | 8 +- wpilibc/sim/src/DriverStation.cpp | 6 +- wpilibc/sim/src/Encoder.cpp | 8 +- wpilibc/sim/src/Notifier.cpp | 5 +- wpilibc/sim/src/PWM.cpp | 14 +-- wpilibc/sim/src/Relay.cpp | 18 ++-- wpilibc/sim/src/Solenoid.cpp | 8 +- wpilibc/sim/src/Timer.cpp | 2 +- wpilibc/sim/src/Utility.cpp | 4 +- .../src/AnalogLoopTest.cpp | 6 +- .../src/AnalogPotentiometerTest.cpp | 4 +- wpilibcIntegrationTests/src/CANJaguarTest.cpp | 4 +- .../src/ConditionVariableTest.cpp | 2 +- wpilibcIntegrationTests/src/CounterTest.cpp | 4 +- wpilibcIntegrationTests/src/DIOLoopTest.cpp | 6 +- .../src/FakeEncoderTest.cpp | 4 +- .../src/FilterOutputTest.cpp | 2 +- .../src/MotorEncoderTest.cpp | 4 +- .../src/MotorInvertingTest.cpp | 4 +- wpilibcIntegrationTests/src/MutexTest.cpp | 12 +-- wpilibcIntegrationTests/src/PCMTest.cpp | 4 +- .../src/PIDToleranceTest.cpp | 15 ++- .../src/PowerDistributionPanelTest.cpp | 4 +- wpilibcIntegrationTests/src/RelayTest.cpp | 6 +- .../src/TestEnvironment.cpp | 4 +- .../src/TiltPanCameraTest.cpp | 4 +- wpilibcIntegrationTests/src/TimerTest.cpp | 4 +- .../src/command/CommandTest.cpp | 6 +- .../java/edu/wpi/first/wpilibj/PWM.java | 4 +- .../first/wpilibj/PWMConfigDataResult.java | 10 +- .../edu/wpi/first/wpilibj/hal/PWMJNI.java | 22 ++--- 141 files changed, 670 insertions(+), 626 deletions(-) diff --git a/hal/include/HAL/DIO.h b/hal/include/HAL/DIO.h index 2eedfb2c65..76693423a0 100644 --- a/hal/include/HAL/DIO.h +++ b/hal/include/HAL/DIO.h @@ -24,7 +24,7 @@ void HAL_SetDigitalPWMDutyCycle(HAL_DigitalPWMHandle pwmGenerator, void HAL_SetDigitalPWMOutputChannel(HAL_DigitalPWMHandle pwmGenerator, uint32_t pin, int32_t* status); -void HAL_SetDIO(HAL_DigitalHandle dio_port_handle, short value, +void HAL_SetDIO(HAL_DigitalHandle dio_port_handle, int16_t value, int32_t* status); bool HAL_GetDIO(HAL_DigitalHandle dio_port_handle, int32_t* status); bool HAL_GetDIODirection(HAL_DigitalHandle dio_port_handle, int32_t* status); diff --git a/hal/lib/athena/AnalogGyro.cpp b/hal/lib/athena/AnalogGyro.cpp index 3cb330ad9c..0faf6680a5 100644 --- a/hal/lib/athena/AnalogGyro.cpp +++ b/hal/lib/athena/AnalogGyro.cpp @@ -162,9 +162,11 @@ void HAL_CalibrateAnalogGyro(HAL_GyroHandle handle, int32_t* status) { HAL_GetAccumulatorOutput(gyro->handle, &value, &count, status); if (*status != 0) return; - gyro->center = (uint32_t)((float)value / (float)count + .5); + gyro->center = static_cast( + static_cast(value) / static_cast(count) + .5); - gyro->offset = ((float)value / (float)count) - (float)gyro->center; + gyro->offset = static_cast(value) / static_cast(count) - + static_cast(gyro->center); HAL_SetAccumulatorCenter(gyro->handle, gyro->center, status); if (*status != 0) return; HAL_ResetAnalogGyro(handle, status); @@ -194,14 +196,16 @@ float HAL_GetAnalogGyroAngle(HAL_GyroHandle handle, int32_t* status) { uint32_t count = 0; HAL_GetAccumulatorOutput(gyro->handle, &rawValue, &count, status); - int64_t value = rawValue - (int64_t)((float)count * gyro->offset); + int64_t value = + rawValue - static_cast(static_cast(count) * gyro->offset); double scaledValue = - value * 1e-9 * (double)HAL_GetAnalogLSBWeight(gyro->handle, status) * - (double)(1 << HAL_GetAnalogAverageBits(gyro->handle, status)) / + value * 1e-9 * + static_cast(HAL_GetAnalogLSBWeight(gyro->handle, status)) * + static_cast(1 << HAL_GetAnalogAverageBits(gyro->handle, status)) / (HAL_GetAnalogSampleRate(status) * gyro->voltsPerDegreePerSecond); - return (float)scaledValue; + return static_cast(scaledValue); } double HAL_GetAnalogGyroRate(HAL_GyroHandle handle, int32_t* status) { @@ -212,7 +216,7 @@ double HAL_GetAnalogGyroRate(HAL_GyroHandle handle, int32_t* status) { } return (HAL_GetAnalogAverageValue(gyro->handle, status) - - ((double)gyro->center + gyro->offset)) * + (static_cast(gyro->center) + gyro->offset)) * 1e-9 * HAL_GetAnalogLSBWeight(gyro->handle, status) / ((1 << HAL_GetAnalogOversampleBits(gyro->handle, status)) * gyro->voltsPerDegreePerSecond); diff --git a/hal/lib/athena/AnalogInput.cpp b/hal/lib/athena/AnalogInput.cpp index ff96e2895d..397b12c765 100644 --- a/hal/lib/athena/AnalogInput.cpp +++ b/hal/lib/athena/AnalogInput.cpp @@ -51,8 +51,9 @@ HAL_AnalogInputHandle HAL_InitializeAnalogInputPort(HAL_PortHandle port_handle, analog_port->pin = static_cast(pin); if (HAL_IsAccumulatorChannel(handle, status)) { analog_port->accumulator = tAccumulator::create(pin, status); - } else + } else { analog_port->accumulator = nullptr; + } // Set default configuration analogInputSystem->writeScanList(pin, pin, status); @@ -102,7 +103,8 @@ void HAL_SetAnalogSampleRate(double samplesPerSecond, int32_t* status) { analogSampleRateSet = true; // Compute the convert rate - uint32_t ticksPerSample = (uint32_t)((float)kTimebase / samplesPerSecond); + uint32_t ticksPerSample = + static_cast(static_cast(kTimebase) / samplesPerSecond); uint32_t ticksPerConversion = ticksPerSample / getAnalogNumChannelsToActivate(status); // ticksPerConversion must be at least 80 @@ -134,7 +136,7 @@ float HAL_GetAnalogSampleRate(int32_t* status) { uint32_t ticksPerConversion = analogInputSystem->readLoopTiming(status); uint32_t ticksPerSample = ticksPerConversion * getAnalogNumActiveChannels(status); - return (float)kTimebase / (float)ticksPerSample; + return static_cast(kTimebase) / static_cast(ticksPerSample); } /** @@ -317,7 +319,7 @@ float HAL_GetAnalogAverageVoltage(HAL_AnalogInputHandle analog_port_handle, uint32_t oversampleBits = HAL_GetAnalogOversampleBits(analog_port_handle, status); float voltage = - ((LSBWeight * 1.0e-9 * value) / (float)(1 << oversampleBits)) - + LSBWeight * 1.0e-9 * value / static_cast(1 << oversampleBits) - offset * 1.0e-9; return voltage; } diff --git a/hal/lib/athena/AnalogInternal.cpp b/hal/lib/athena/AnalogInternal.cpp index a44d5baa17..eb3cd15391 100644 --- a/hal/lib/athena/AnalogInternal.cpp +++ b/hal/lib/athena/AnalogInternal.cpp @@ -78,4 +78,4 @@ uint32_t getAnalogNumChannelsToActivate(int32_t* status) { void setAnalogNumChannelsToActivate(uint32_t channels) { analogNumChannelsToActivate = channels; } -} +} // namespace hal diff --git a/hal/lib/athena/AnalogInternal.h b/hal/lib/athena/AnalogInternal.h index 3d5d5d366a..328e85c680 100644 --- a/hal/lib/athena/AnalogInternal.h +++ b/hal/lib/athena/AnalogInternal.h @@ -16,9 +16,9 @@ #include "handles/IndexedHandleResource.h" namespace hal { -constexpr long kTimebase = 40000000; ///< 40 MHz clock -constexpr long kDefaultOversampleBits = 0; -constexpr long kDefaultAverageBits = 7; +constexpr int32_t kTimebase = 40000000; ///< 40 MHz clock +constexpr int32_t kDefaultOversampleBits = 0; +constexpr int32_t kDefaultAverageBits = 7; constexpr float kDefaultSampleRate = 50000.0; static const uint32_t kAccumulatorChannels[] = {0, 1}; @@ -41,4 +41,4 @@ void setAnalogNumChannelsToActivate(uint32_t channels); void initializeAnalog(int32_t* status); extern bool analogSystemInitialized; -} +} // namespace hal diff --git a/hal/lib/athena/Counter.cpp b/hal/lib/athena/Counter.cpp index cc3f1d354f..d98462de8e 100644 --- a/hal/lib/athena/Counter.cpp +++ b/hal/lib/athena/Counter.cpp @@ -362,7 +362,8 @@ double HAL_GetCounterPeriod(HAL_CounterHandle counter_handle, int32_t* status) { } else { // output.Period is a fixed point number that counts by 2 (24 bits, 25 // integer bits) - period = (double)(output.Period << 1) / (double)output.Count; + period = static_cast(output.Period << 1) / + static_cast(output.Count); } return period * 2.5e-8; // result * timebase (currently 40ns) } diff --git a/hal/lib/athena/DIO.cpp b/hal/lib/athena/DIO.cpp index 68e9f86145..e2f96835c6 100644 --- a/hal/lib/athena/DIO.cpp +++ b/hal/lib/athena/DIO.cpp @@ -70,7 +70,7 @@ HAL_DigitalHandle HAL_InitializeDIOPort(HAL_PortHandle port_handle, uint32_t bitToSet = 1 << remapMXPChannel(port->pin); // Disable special functions on this pin - short specialFunctions = + int16_t specialFunctions = digitalSystem->readEnableMXPSpecialFunction(status); digitalSystem->writeEnableMXPSpecialFunction(specialFunctions & ~bitToSet, status); @@ -207,7 +207,7 @@ void HAL_SetDigitalPWMOutputChannel(HAL_DigitalPWMHandle pwmGenerator, * @param value The state to set the digital channel (if it is configured as an * output) */ -void HAL_SetDIO(HAL_DigitalHandle dio_port_handle, short value, +void HAL_SetDIO(HAL_DigitalHandle dio_port_handle, int16_t value, int32_t* status) { auto port = digitalPinHandles.Get(dio_port_handle, HAL_HandleEnum::DIO); if (port == nullptr) { @@ -235,7 +235,7 @@ void HAL_SetDIO(HAL_DigitalHandle dio_port_handle, short value, } uint32_t bitToSet = 1 << remapMXPChannel(port->pin); - short specialFunctions = + int16_t specialFunctions = digitalSystem->readEnableMXPSpecialFunction(status); digitalSystem->writeEnableMXPSpecialFunction(specialFunctions & ~bitToSet, status); @@ -268,7 +268,7 @@ bool HAL_GetDIO(HAL_DigitalHandle dio_port_handle, int32_t* status) { } else { // Disable special functions uint32_t bitToSet = 1 << remapMXPChannel(port->pin); - short specialFunctions = + int16_t specialFunctions = digitalSystem->readEnableMXPSpecialFunction(status); digitalSystem->writeEnableMXPSpecialFunction(specialFunctions & ~bitToSet, status); diff --git a/hal/lib/athena/DigitalInternal.cpp b/hal/lib/athena/DigitalInternal.cpp index 4f2b7bbf24..b6b9932978 100644 --- a/hal/lib/athena/DigitalInternal.cpp +++ b/hal/lib/athena/DigitalInternal.cpp @@ -134,4 +134,4 @@ bool remapDigitalSource(HAL_Handle digitalSourceHandle, return false; } } -} +} // namespace hal diff --git a/hal/lib/athena/DigitalInternal.h b/hal/lib/athena/DigitalInternal.h index 81d1bbc2ba..1a5b34e267 100644 --- a/hal/lib/athena/DigitalInternal.h +++ b/hal/lib/athena/DigitalInternal.h @@ -82,4 +82,4 @@ bool remapDigitalSource(HAL_Handle digitalSourceHandle, uint8_t& module, bool& analogTrigger); uint32_t remapMXPPWMChannel(uint32_t pin); uint32_t remapMXPChannel(uint32_t pin); -} +} // namespace hal diff --git a/hal/lib/athena/EncoderInternal.h b/hal/lib/athena/EncoderInternal.h index 7a5af6dfc0..87488981d6 100644 --- a/hal/lib/athena/EncoderInternal.h +++ b/hal/lib/athena/EncoderInternal.h @@ -73,4 +73,4 @@ class Encoder { int32_t m_encodingScale; }; -} +} // namespace hal diff --git a/hal/lib/athena/FPGAEncoder.cpp b/hal/lib/athena/FPGAEncoder.cpp index 1b219a0774..17457860a8 100644 --- a/hal/lib/athena/FPGAEncoder.cpp +++ b/hal/lib/athena/FPGAEncoder.cpp @@ -148,7 +148,8 @@ double HAL_GetFPGAEncoderPeriod(HAL_FPGAEncoderHandle fpga_encoder_handle, } else { // output.Period is a fixed point number that counts by 2 (24 bits, 25 // integer bits) - value = (double)(output.Period << 1) / (double)output.Count; + value = static_cast(output.Period << 1) / + static_cast(output.Count); } double measuredPeriod = value * 2.5e-8; return measuredPeriod / DECODING_SCALING_FACTOR; diff --git a/hal/lib/athena/HALAthena.cpp b/hal/lib/athena/HALAthena.cpp index 1732a64fd0..769f7c2074 100644 --- a/hal/lib/athena/HALAthena.cpp +++ b/hal/lib/athena/HALAthena.cpp @@ -342,10 +342,10 @@ int HAL_Initialize(int mode) { if (mode == 0) { std::cout << "FRC pid " << pid << " did not die within 110ms. Aborting" << std::endl; - return 0; // just fail - } else if (mode == 1) // kill -9 it + return 0; // just fail + } else if (mode == 1) { // kill -9 it kill(pid, SIGKILL); - else { + } else { std::cout << "WARNING: FRC pid " << pid << " did not die within 110ms." << std::endl; } diff --git a/hal/lib/athena/I2C.cpp b/hal/lib/athena/I2C.cpp index 9f7b91ad09..3a904da074 100644 --- a/hal/lib/athena/I2C.cpp +++ b/hal/lib/athena/I2C.cpp @@ -94,9 +94,10 @@ int32_t HAL_TransactionI2C(uint8_t port, uint8_t deviceAddress, { std::lock_guard sync(lock); - return i2clib_writeread(handle, deviceAddress, (const char*)dataToSend, - (int32_t)sendSize, (char*)dataReceived, - (int32_t)receiveSize); + return i2clib_writeread( + handle, deviceAddress, reinterpret_cast(dataToSend), + static_cast(sendSize), reinterpret_cast(dataReceived), + static_cast(receiveSize)); } } @@ -153,7 +154,8 @@ int32_t HAL_ReadI2C(uint8_t port, uint8_t deviceAddress, uint8_t* buffer, port == 0 ? digitalI2COnBoardMutex : digitalI2CMXPMutex; { std::lock_guard sync(lock); - return i2clib_read(handle, deviceAddress, (char*)buffer, (int32_t)count); + return i2clib_read(handle, deviceAddress, reinterpret_cast(buffer), + static_cast(count)); } } diff --git a/hal/lib/athena/Interrupts.cpp b/hal/lib/athena/Interrupts.cpp index 34551f444e..d51278fe98 100644 --- a/hal/lib/athena/Interrupts.cpp +++ b/hal/lib/athena/Interrupts.cpp @@ -20,8 +20,8 @@ using namespace hal; namespace { -struct Interrupt // FIXME: why is this internal? -{ +// FIXME: why is this internal? +struct Interrupt { tInterrupt* anInterrupt; tInterruptManager* manager; }; diff --git a/hal/lib/athena/PWM.cpp b/hal/lib/athena/PWM.cpp index ecfa13a583..0e48f1acad 100644 --- a/hal/lib/athena/PWM.cpp +++ b/hal/lib/athena/PWM.cpp @@ -75,7 +75,8 @@ HAL_DigitalHandle HAL_InitializePWMPort(HAL_PortHandle port_handle, port->pin = origPin; uint32_t bitToSet = 1 << remapMXPPWMChannel(port->pin); - short specialFunctions = digitalSystem->readEnableMXPSpecialFunction(status); + int16_t specialFunctions = + digitalSystem->readEnableMXPSpecialFunction(status); digitalSystem->writeEnableMXPSpecialFunction(specialFunctions | bitToSet, status); @@ -90,7 +91,7 @@ void HAL_FreePWMPort(HAL_DigitalHandle pwm_port_handle, int32_t* status) { if (port->pin > tPWM::kNumHdrRegisters - 1) { uint32_t bitToUnset = 1 << remapMXPPWMChannel(port->pin); - short specialFunctions = + int16_t specialFunctions = digitalSystem->readEnableMXPSpecialFunction(status); digitalSystem->writeEnableMXPSpecialFunction(specialFunctions & ~bitToUnset, status); @@ -244,11 +245,13 @@ void HAL_SetPWMSpeed(HAL_DigitalHandle pwm_port_handle, float speed, if (speed == 0.0) { rawValue = GetCenterPwm(dPort); } else if (speed > 0.0) { - rawValue = (int32_t)(speed * ((float)GetPositiveScaleFactor(dPort)) + - ((float)GetMinPositivePwm(dPort)) + 0.5); + rawValue = static_cast( + speed * static_cast(GetPositiveScaleFactor(dPort)) + + static_cast(GetMinPositivePwm(dPort)) + 0.5); } else { - rawValue = (int32_t)(speed * ((float)GetNegativeScaleFactor(dPort)) + - ((float)GetMaxNegativePwm(dPort)) + 0.5); + rawValue = static_cast( + speed * static_cast(GetNegativeScaleFactor(dPort)) + + static_cast(GetMaxNegativePwm(dPort)) + 0.5); } if (!((rawValue >= GetMinNegativePwm(dPort)) && @@ -291,8 +294,9 @@ void HAL_SetPWMPosition(HAL_DigitalHandle pwm_port_handle, float pos, // note, need to perform the multiplication below as floating point before // converting to int - uint16_t rawValue = (int32_t)((pos * (float)GetFullRangeScaleFactor(dPort)) + - GetMinNegativePwm(dPort)); + uint16_t rawValue = static_cast( + (pos * static_cast(GetFullRangeScaleFactor(dPort))) + + GetMinNegativePwm(dPort)); if (rawValue == kPwmDisabled) { *status = HAL_PWM_SCALE_ERROR; @@ -354,11 +358,11 @@ float HAL_GetPWMSpeed(HAL_DigitalHandle pwm_port_handle, int32_t* status) { } else if (value < GetMinNegativePwm(dPort)) { return -1.0; } else if (value > GetMinPositivePwm(dPort)) { - return (float)(value - GetMinPositivePwm(dPort)) / - (float)GetPositiveScaleFactor(dPort); + return static_cast(value - GetMinPositivePwm(dPort)) / + static_cast(GetPositiveScaleFactor(dPort)); } else if (value < GetMaxNegativePwm(dPort)) { - return (float)(value - GetMaxNegativePwm(dPort)) / - (float)GetNegativeScaleFactor(dPort); + return static_cast(value - GetMaxNegativePwm(dPort)) / + static_cast(GetNegativeScaleFactor(dPort)); } else { return 0.0; } @@ -390,8 +394,8 @@ float HAL_GetPWMPosition(HAL_DigitalHandle pwm_port_handle, int32_t* status) { } else if (value > GetMaxPositivePwm(dPort)) { return 1.0; } else { - return (float)(value - GetMinNegativePwm(dPort)) / - (float)GetFullRangeScaleFactor(dPort); + return static_cast(value - GetMinNegativePwm(dPort)) / + static_cast(GetFullRangeScaleFactor(dPort)); } } diff --git a/hal/lib/athena/PortsInternal.h b/hal/lib/athena/PortsInternal.h index ed505f8943..3ea9e9d2dc 100644 --- a/hal/lib/athena/PortsInternal.h +++ b/hal/lib/athena/PortsInternal.h @@ -32,4 +32,4 @@ constexpr int32_t kNumSolenoidPins = 8; constexpr int32_t kNumPDPModules = 63; constexpr int32_t kNumPDPChannels = 16; constexpr int32_t kNumCanTalons = 63; -} +} // namespace hal diff --git a/hal/lib/athena/Power.cpp b/hal/lib/athena/Power.cpp index 84b2755bac..0cf256d4f7 100644 --- a/hal/lib/athena/Power.cpp +++ b/hal/lib/athena/Power.cpp @@ -64,7 +64,8 @@ bool HAL_GetUserActive6V(int32_t* status) { */ int HAL_GetUserCurrentFaults6V(int32_t* status) { initializePower(status); - return (int)power->readFaultCounts_OverCurrentFaultCount6V(status); + return static_cast( + power->readFaultCounts_OverCurrentFaultCount6V(status)); } /** @@ -96,7 +97,8 @@ bool HAL_GetUserActive5V(int32_t* status) { */ int HAL_GetUserCurrentFaults5V(int32_t* status) { initializePower(status); - return (int)power->readFaultCounts_OverCurrentFaultCount5V(status); + return static_cast( + power->readFaultCounts_OverCurrentFaultCount5V(status)); } unsigned char HAL_GetUserStatus5V(int32_t* status) { @@ -133,7 +135,8 @@ bool HAL_GetUserActive3V3(int32_t* status) { */ int HAL_GetUserCurrentFaults3V3(int32_t* status) { initializePower(status); - return (int)power->readFaultCounts_OverCurrentFaultCount3V3(status); + return static_cast( + power->readFaultCounts_OverCurrentFaultCount3V3(status)); } } // extern "C" diff --git a/hal/lib/athena/SPI.cpp b/hal/lib/athena/SPI.cpp index 0aaf990bf6..e82d21dd5a 100644 --- a/hal/lib/athena/SPI.cpp +++ b/hal/lib/athena/SPI.cpp @@ -152,8 +152,9 @@ void HAL_InitializeSPI(uint8_t port, int32_t* status) { int32_t HAL_TransactionSPI(uint8_t port, uint8_t* dataToSend, uint8_t* dataReceived, uint8_t size) { std::lock_guard sync(spiGetSemaphore(port)); - return spilib_writeread(HAL_GetSPIHandle(port), (const char*)dataToSend, - (char*)dataReceived, (int32_t)size); + return spilib_writeread( + HAL_GetSPIHandle(port), reinterpret_cast(dataToSend), + reinterpret_cast(dataReceived), static_cast(size)); } /** @@ -168,8 +169,9 @@ int32_t HAL_TransactionSPI(uint8_t port, uint8_t* dataToSend, */ int32_t HAL_WriteSPI(uint8_t port, uint8_t* dataToSend, uint8_t sendSize) { std::lock_guard sync(spiGetSemaphore(port)); - return spilib_write(HAL_GetSPIHandle(port), (const char*)dataToSend, - (int32_t)sendSize); + return spilib_write(HAL_GetSPIHandle(port), + reinterpret_cast(dataToSend), + static_cast(sendSize)); } /** @@ -187,7 +189,8 @@ int32_t HAL_WriteSPI(uint8_t port, uint8_t* dataToSend, uint8_t sendSize) { */ int32_t HAL_ReadSPI(uint8_t port, uint8_t* buffer, uint8_t count) { std::lock_guard sync(spiGetSemaphore(port)); - return spilib_read(HAL_GetSPIHandle(port), (char*)buffer, (int32_t)count); + return spilib_read(HAL_GetSPIHandle(port), reinterpret_cast(buffer), + static_cast(count)); } /** @@ -325,13 +328,14 @@ void HAL_SetSPIHandle(uint8_t port, int32_t handle) { } static void spiAccumulatorProcess(uint64_t currentTime, void* param) { - SPIAccumulator* accum = (SPIAccumulator*)param; + SPIAccumulator* accum = static_cast(param); // perform SPI transaction uint8_t resp_b[4]; std::lock_guard sync(spiGetSemaphore(accum->port)); - spilib_writeread(HAL_GetSPIHandle(accum->port), (const char*)accum->cmd, - (char*)resp_b, (int32_t)accum->xfer_size); + spilib_writeread( + HAL_GetSPIHandle(accum->port), reinterpret_cast(accum->cmd), + reinterpret_cast(resp_b), static_cast(accum->xfer_size)); // convert from bytes uint32_t resp = 0; @@ -350,7 +354,7 @@ static void spiAccumulatorProcess(uint64_t currentTime, void* param) { // process response if ((resp & accum->valid_mask) == accum->valid_value) { // valid sensor data; extract data field - int32_t data = (int32_t)(resp >> accum->data_shift); + int32_t data = static_cast(resp >> accum->data_shift); data &= accum->data_max - 1; // 2s complement conversion if signed MSB is set if (accum->is_signed && (data & accum->data_msb_mask) != 0) @@ -553,7 +557,7 @@ double HAL_GetSPIAccumulatorAverage(uint8_t port, int32_t* status) { uint32_t count; HAL_GetAccumulatorOutput(port, &value, &count, status); if (count == 0) return 0.0; - return ((double)value) / count; + return static_cast(value) / count; } /** diff --git a/hal/lib/athena/SerialPort.cpp b/hal/lib/athena/SerialPort.cpp index 530536694b..4cff7eed2e 100644 --- a/hal/lib/athena/SerialPort.cpp +++ b/hal/lib/athena/SerialPort.cpp @@ -18,7 +18,7 @@ void HAL_InitializeSerialPort(uint8_t port, int32_t* status) { char const* portName; if (m_resourceManagerHandle == 0) - viOpenDefaultRM((ViSession*)&m_resourceManagerHandle); + viOpenDefaultRM(reinterpret_cast(&m_resourceManagerHandle)); if (port == 0) portName = "ASRL1::INSTR"; @@ -27,8 +27,9 @@ void HAL_InitializeSerialPort(uint8_t port, int32_t* status) { else portName = "ASRL3::INSTR"; - *status = viOpen(m_resourceManagerHandle, const_cast(portName), - VI_NULL, VI_NULL, (ViSession*)&m_portHandle[port]); + *status = + viOpen(m_resourceManagerHandle, const_cast(portName), VI_NULL, + VI_NULL, reinterpret_cast(&m_portHandle[port])); if (*status > 0) *status = 0; } diff --git a/hal/lib/athena/handles/DigitalHandleResource.h b/hal/lib/athena/handles/DigitalHandleResource.h index ce6602919f..23942b1c04 100644 --- a/hal/lib/athena/handles/DigitalHandleResource.h +++ b/hal/lib/athena/handles/DigitalHandleResource.h @@ -104,4 +104,4 @@ void DigitalHandleResource::Free( std::lock_guard sync(m_handleMutexes[index]); m_structures[index].reset(); } -} +} // namespace hal diff --git a/hal/lib/athena/handles/HandlesInternal.cpp b/hal/lib/athena/handles/HandlesInternal.cpp index 8e0d079072..354abab900 100644 --- a/hal/lib/athena/handles/HandlesInternal.cpp +++ b/hal/lib/athena/handles/HandlesInternal.cpp @@ -35,4 +35,4 @@ HAL_Handle createHandle(int16_t index, HAL_HandleEnum handleType) { handle += index; return handle; } -} +} // namespace hal diff --git a/hal/lib/athena/handles/HandlesInternal.h b/hal/lib/athena/handles/HandlesInternal.h index 304140a2d1..e24a69cf1c 100644 --- a/hal/lib/athena/handles/HandlesInternal.h +++ b/hal/lib/athena/handles/HandlesInternal.h @@ -86,4 +86,4 @@ static inline int16_t getPortHandleModule(HAL_PortHandle handle) { HAL_PortHandle createPortHandle(uint8_t pin, uint8_t module); HAL_Handle createHandle(int16_t index, HAL_HandleEnum handleType); -} +} // namespace hal diff --git a/hal/lib/athena/handles/IndexedHandleResource.h b/hal/lib/athena/handles/IndexedHandleResource.h index d4fc52521c..c1a53dc297 100644 --- a/hal/lib/athena/handles/IndexedHandleResource.h +++ b/hal/lib/athena/handles/IndexedHandleResource.h @@ -112,4 +112,4 @@ void IndexedHandleResource::Free( std::lock_guard sync(m_handleMutexes[index]); m_structures[index].reset(); } -} +} // namespace hal diff --git a/hal/lib/athena/handles/LimitedClassedHandleResource.h b/hal/lib/athena/handles/LimitedClassedHandleResource.h index 2183878786..b55b3fbad9 100644 --- a/hal/lib/athena/handles/LimitedClassedHandleResource.h +++ b/hal/lib/athena/handles/LimitedClassedHandleResource.h @@ -114,4 +114,4 @@ void LimitedClassedHandleResource::Free( std::lock_guard lock(m_handleMutexes[index]); m_structures[index].reset(); } -} +} // namespace hal diff --git a/hal/lib/athena/handles/LimitedHandleResource.h b/hal/lib/athena/handles/LimitedHandleResource.h index e355b41289..65caff61db 100644 --- a/hal/lib/athena/handles/LimitedHandleResource.h +++ b/hal/lib/athena/handles/LimitedHandleResource.h @@ -110,4 +110,4 @@ void LimitedHandleResource::Free( std::lock_guard lock(m_handleMutexes[index]); m_structures[index].reset(); } -} +} // namespace hal diff --git a/hal/lib/athena/handles/UnlimitedHandleResource.h b/hal/lib/athena/handles/UnlimitedHandleResource.h index 6137a79d25..35bb24fcd4 100644 --- a/hal/lib/athena/handles/UnlimitedHandleResource.h +++ b/hal/lib/athena/handles/UnlimitedHandleResource.h @@ -84,4 +84,4 @@ void UnlimitedHandleResource::Free( if (index < 0 || index >= static_cast(m_structures.size())) return; m_structures[index].reset(); } -} +} // namespace hal diff --git a/hal/lib/shared/HAL.cpp b/hal/lib/shared/HAL.cpp index 11d38bfae2..d1a702d89a 100644 --- a/hal/lib/shared/HAL.cpp +++ b/hal/lib/shared/HAL.cpp @@ -39,7 +39,8 @@ int HAL_GetJoystickAxes(uint8_t joystickNum, HAL_JoystickAxes* axes) { HAL_JoystickAxesInt axesInt; int retVal = FRC_NetworkCommunication_getJoystickAxes( - joystickNum, (JoystickAxes_t*)&axesInt, HAL_kMaxJoystickAxes); + joystickNum, reinterpret_cast(&axesInt), + HAL_kMaxJoystickAxes); // copy int values to float values axes->count = axesInt.count; @@ -59,7 +60,8 @@ int HAL_GetJoystickAxes(uint8_t joystickNum, HAL_JoystickAxes* axes) { int HAL_GetJoystickPOVs(uint8_t joystickNum, HAL_JoystickPOVs* povs) { return FRC_NetworkCommunication_getJoystickPOVs( - joystickNum, (JoystickPOV_t*)povs, HAL_kMaxJoystickPOVs); + joystickNum, reinterpret_cast(povs), + HAL_kMaxJoystickPOVs); } int HAL_GetJoystickButtons(uint8_t joystickNum, HAL_JoystickButtons* buttons) { @@ -87,8 +89,9 @@ int HAL_GetJoystickDescriptor(uint8_t joystickNum, desc->buttonCount = 0; desc->povCount = 0; int retval = FRC_NetworkCommunication_getJoystickDesc( - joystickNum, &desc->isXbox, &desc->type, (char*)(&desc->name), - &desc->axisCount, (uint8_t*)&desc->axisTypes, &desc->buttonCount, + joystickNum, &desc->isXbox, &desc->type, + reinterpret_cast(&desc->name), &desc->axisCount, + reinterpret_cast(&desc->axisTypes), &desc->buttonCount, &desc->povCount); /* check the return, if there is an error and the RIOimage predates FRC2017, * then axisCount needs to be cleared */ @@ -120,13 +123,14 @@ int HAL_GetJoystickType(uint8_t joystickNum) { char* HAL_GetJoystickName(uint8_t joystickNum) { HAL_JoystickDescriptor joystickDesc; if (HAL_GetJoystickDescriptor(joystickNum, &joystickDesc) < 0) { - char* name = (char*)std::malloc(1); + char* name = static_cast(std::malloc(1)); name[0] = '\0'; return name; } else { size_t len = std::strlen(joystickDesc.name); - char* name = (char*)std::malloc(len + 1); - std::strcpy(name, joystickDesc.name); + char* name = static_cast(std::malloc(len + 1)); + std::strncpy(name, joystickDesc.name, len); + name[len] = '\0'; return name; } } diff --git a/simulation/frc_gazebo_plugins/limit_switch/src/external_limit_switch.h b/simulation/frc_gazebo_plugins/limit_switch/src/external_limit_switch.h index 2c453c199e..4be5363d4e 100644 --- a/simulation/frc_gazebo_plugins/limit_switch/src/external_limit_switch.h +++ b/simulation/frc_gazebo_plugins/limit_switch/src/external_limit_switch.h @@ -21,7 +21,7 @@ using namespace gazebo; class ExternalLimitSwitch : public Switch { public: - ExternalLimitSwitch(sdf::ElementPtr sdf); + explicit ExternalLimitSwitch(sdf::ElementPtr sdf); /// \brief Returns true when the switch is triggered. virtual bool Get(); diff --git a/wpilibc/athena/include/ADXL345_I2C.h b/wpilibc/athena/include/ADXL345_I2C.h index 495c598e70..9cc7b741cb 100644 --- a/wpilibc/athena/include/ADXL345_I2C.h +++ b/wpilibc/athena/include/ADXL345_I2C.h @@ -59,20 +59,20 @@ class ADXL345_I2C : public Accelerometer, public LiveWindowSendable { ADXL345_I2C& operator=(const ADXL345_I2C&) = delete; // Accelerometer interface - virtual void SetRange(Range range) override; - virtual double GetX() override; - virtual double GetY() override; - virtual double GetZ() override; + void SetRange(Range range) override; + double GetX() override; + double GetY() override; + double GetZ() override; virtual double GetAcceleration(Axes axis); virtual AllAxes GetAccelerations(); - virtual std::string GetSmartDashboardType() const override; - virtual void InitTable(std::shared_ptr subtable) override; - virtual void UpdateTable() override; - virtual std::shared_ptr GetTable() const override; - virtual void StartLiveWindowMode() override {} - virtual void StopLiveWindowMode() override {} + std::string GetSmartDashboardType() const override; + void InitTable(std::shared_ptr subtable) override; + void UpdateTable() override; + std::shared_ptr GetTable() const override; + void StartLiveWindowMode() override {} + void StopLiveWindowMode() override {} protected: I2C m_i2c; diff --git a/wpilibc/athena/include/ADXL345_SPI.h b/wpilibc/athena/include/ADXL345_SPI.h index 9427f2805c..ef417f9c8a 100644 --- a/wpilibc/athena/include/ADXL345_SPI.h +++ b/wpilibc/athena/include/ADXL345_SPI.h @@ -54,27 +54,27 @@ class ADXL345_SPI : public Accelerometer, public LiveWindowSendable { }; public: - ADXL345_SPI(SPI::Port port, Range range = kRange_2G); + explicit ADXL345_SPI(SPI::Port port, Range range = kRange_2G); virtual ~ADXL345_SPI() = default; ADXL345_SPI(const ADXL345_SPI&) = delete; ADXL345_SPI& operator=(const ADXL345_SPI&) = delete; // Accelerometer interface - virtual void SetRange(Range range) override; - virtual double GetX() override; - virtual double GetY() override; - virtual double GetZ() override; + void SetRange(Range range) override; + double GetX() override; + double GetY() override; + double GetZ() override; virtual double GetAcceleration(Axes axis); virtual AllAxes GetAccelerations(); - virtual std::string GetSmartDashboardType() const override; - virtual void InitTable(std::shared_ptr subtable) override; - virtual void UpdateTable() override; - virtual std::shared_ptr GetTable() const override; - virtual void StartLiveWindowMode() override {} - virtual void StopLiveWindowMode() override {} + std::string GetSmartDashboardType() const override; + void InitTable(std::shared_ptr subtable) override; + void UpdateTable() override; + std::shared_ptr GetTable() const override; + void StartLiveWindowMode() override {} + void StopLiveWindowMode() override {} protected: SPI m_spi; diff --git a/wpilibc/athena/include/ADXL362.h b/wpilibc/athena/include/ADXL362.h index 66f1e5d95d..2cdb9a75d9 100644 --- a/wpilibc/athena/include/ADXL362.h +++ b/wpilibc/athena/include/ADXL362.h @@ -32,28 +32,28 @@ class ADXL362 : public Accelerometer, public LiveWindowSendable { }; public: - ADXL362(Range range = kRange_2G); - ADXL362(SPI::Port port, Range range = kRange_2G); + explicit ADXL362(Range range = kRange_2G); + explicit ADXL362(SPI::Port port, Range range = kRange_2G); virtual ~ADXL362() = default; ADXL362(const ADXL362&) = delete; ADXL362& operator=(const ADXL362&) = delete; // Accelerometer interface - virtual void SetRange(Range range) override; - virtual double GetX() override; - virtual double GetY() override; - virtual double GetZ() override; + void SetRange(Range range) override; + double GetX() override; + double GetY() override; + double GetZ() override; virtual double GetAcceleration(Axes axis); virtual AllAxes GetAccelerations(); - virtual std::string GetSmartDashboardType() const override; - virtual void InitTable(std::shared_ptr subtable) override; - virtual void UpdateTable() override; - virtual std::shared_ptr GetTable() const override; - virtual void StartLiveWindowMode() override {} - virtual void StopLiveWindowMode() override {} + std::string GetSmartDashboardType() const override; + void InitTable(std::shared_ptr subtable) override; + void UpdateTable() override; + std::shared_ptr GetTable() const override; + void StartLiveWindowMode() override {} + void StopLiveWindowMode() override {} private: SPI m_spi; diff --git a/wpilibc/athena/include/AnalogPotentiometer.h b/wpilibc/athena/include/AnalogPotentiometer.h index 39622ccc35..065e05b3b7 100644 --- a/wpilibc/athena/include/AnalogPotentiometer.h +++ b/wpilibc/athena/include/AnalogPotentiometer.h @@ -53,34 +53,34 @@ class AnalogPotentiometer : public Potentiometer, public LiveWindowSendable { * * @return The current position of the potentiometer. */ - virtual double Get() const override; + double Get() const override; /** * Implement the PIDSource interface. * * @return The current reading. */ - virtual double PIDGet() override; + double PIDGet() override; /* * Live Window code, only does anything if live window is activated. */ - virtual std::string GetSmartDashboardType() const override; - virtual void InitTable(std::shared_ptr subtable) override; - virtual void UpdateTable() override; - virtual std::shared_ptr GetTable() const override; + std::string GetSmartDashboardType() const override; + void InitTable(std::shared_ptr subtable) override; + void UpdateTable() override; + std::shared_ptr GetTable() const override; /** * AnalogPotentiometers don't have to do anything special when entering the * LiveWindow. */ - virtual void StartLiveWindowMode() override {} + void StartLiveWindowMode() override {} /** * AnalogPotentiometers don't have to do anything special when exiting the * LiveWindow. */ - virtual void StopLiveWindowMode() override {} + void StopLiveWindowMode() override {} private: std::shared_ptr m_analog_input; diff --git a/wpilibc/athena/include/AnalogTriggerOutput.h b/wpilibc/athena/include/AnalogTriggerOutput.h index 45a8c3973c..a9111a0509 100644 --- a/wpilibc/athena/include/AnalogTriggerOutput.h +++ b/wpilibc/athena/include/AnalogTriggerOutput.h @@ -49,10 +49,10 @@ class AnalogTriggerOutput : public DigitalSource { bool Get() const; // DigitalSource interface - virtual HAL_Handle GetPortHandleForRouting() const override; - virtual AnalogTriggerType GetAnalogTriggerTypeForRouting() const override; - virtual bool IsAnalogTrigger() const override; - virtual uint32_t GetChannel() const override; + HAL_Handle GetPortHandleForRouting() const override; + AnalogTriggerType GetAnalogTriggerTypeForRouting() const override; + bool IsAnalogTrigger() const override; + uint32_t GetChannel() const override; protected: AnalogTriggerOutput(const AnalogTrigger& trigger, diff --git a/wpilibc/athena/include/AnalogTriggerType.h b/wpilibc/athena/include/AnalogTriggerType.h index 88c58c7556..6c99ddc0f8 100644 --- a/wpilibc/athena/include/AnalogTriggerType.h +++ b/wpilibc/athena/include/AnalogTriggerType.h @@ -12,4 +12,4 @@ enum class AnalogTriggerType { kState = 1, kRisingPulse = 2, kFallingPulse = 3 -}; \ No newline at end of file +}; diff --git a/wpilibc/athena/include/BuiltInAccelerometer.h b/wpilibc/athena/include/BuiltInAccelerometer.h index ccc1633af5..c1ae09d9be 100644 --- a/wpilibc/athena/include/BuiltInAccelerometer.h +++ b/wpilibc/athena/include/BuiltInAccelerometer.h @@ -22,21 +22,21 @@ class BuiltInAccelerometer : public Accelerometer, public SensorBase, public LiveWindowSendable { public: - BuiltInAccelerometer(Range range = kRange_8G); + explicit BuiltInAccelerometer(Range range = kRange_8G); virtual ~BuiltInAccelerometer() = default; // Accelerometer interface - virtual void SetRange(Range range) override; - virtual double GetX() override; - virtual double GetY() override; - virtual double GetZ() override; + void SetRange(Range range) override; + double GetX() override; + double GetY() override; + double GetZ() override; - virtual std::string GetSmartDashboardType() const override; - virtual void InitTable(std::shared_ptr subtable) override; - virtual void UpdateTable() override; - virtual std::shared_ptr GetTable() const override; - virtual void StartLiveWindowMode() override {} - virtual void StopLiveWindowMode() override {} + std::string GetSmartDashboardType() const override; + void InitTable(std::shared_ptr subtable) override; + void UpdateTable() override; + std::shared_ptr GetTable() const override; + void StartLiveWindowMode() override {} + void StopLiveWindowMode() override {} private: std::shared_ptr m_table; diff --git a/wpilibc/athena/include/CANJaguar.h b/wpilibc/athena/include/CANJaguar.h index 41f8c17b23..f1c406ea53 100644 --- a/wpilibc/athena/include/CANJaguar.h +++ b/wpilibc/athena/include/CANJaguar.h @@ -59,7 +59,7 @@ class CANJaguar : public MotorSafety, uint8_t GetHardwareVersion() const; // PIDOutput interface - virtual void PIDWrite(float output) override; + void PIDWrite(float output) override; // Control mode methods void EnableControl(double encoderInitialPosition = 0.0); @@ -94,39 +94,39 @@ class CANJaguar : public MotorSafety, void Set(float value, uint8_t syncGroup); // CANSpeedController interface - virtual float Get() const override; - virtual void Set(float value) override; - virtual void Disable() override; - virtual void SetP(double p) override; - virtual void SetI(double i) override; - virtual void SetD(double d) override; - virtual void SetPID(double p, double i, double d) override; - virtual double GetP() const override; - virtual double GetI() const override; - virtual double GetD() const override; - virtual bool IsModePID(CANSpeedController::ControlMode mode) const override; - virtual float GetBusVoltage() const override; - virtual float GetOutputVoltage() const override; - virtual float GetOutputCurrent() const override; - virtual float GetTemperature() const override; - virtual double GetPosition() const override; - virtual double GetSpeed() const override; - virtual bool GetForwardLimitOK() const override; - virtual bool GetReverseLimitOK() const override; - virtual uint16_t GetFaults() const override; - virtual void SetVoltageRampRate(double rampRate) override; - virtual uint32_t GetFirmwareVersion() const override; - virtual void ConfigNeutralMode(NeutralMode mode) override; - virtual void ConfigEncoderCodesPerRev(uint16_t codesPerRev) override; - virtual void ConfigPotentiometerTurns(uint16_t turns) override; - virtual void ConfigSoftPositionLimits(double forwardLimitPosition, - double reverseLimitPosition) override; - virtual void DisableSoftPositionLimits() override; - virtual void ConfigLimitMode(LimitMode mode) override; - virtual void ConfigForwardLimit(double forwardLimitPosition) override; - virtual void ConfigReverseLimit(double reverseLimitPosition) override; - virtual void ConfigMaxOutputVoltage(double voltage) override; - virtual void ConfigFaultTime(float faultTime) override; + float Get() const override; + void Set(float value) override; + void Disable() override; + void SetP(double p) override; + void SetI(double i) override; + void SetD(double d) override; + void SetPID(double p, double i, double d) override; + double GetP() const override; + double GetI() const override; + double GetD() const override; + bool IsModePID(CANSpeedController::ControlMode mode) const override; + float GetBusVoltage() const override; + float GetOutputVoltage() const override; + float GetOutputCurrent() const override; + float GetTemperature() const override; + double GetPosition() const override; + double GetSpeed() const override; + bool GetForwardLimitOK() const override; + bool GetReverseLimitOK() const override; + uint16_t GetFaults() const override; + void SetVoltageRampRate(double rampRate) override; + uint32_t GetFirmwareVersion() const override; + void ConfigNeutralMode(NeutralMode mode) override; + void ConfigEncoderCodesPerRev(uint16_t codesPerRev) override; + void ConfigPotentiometerTurns(uint16_t turns) override; + void ConfigSoftPositionLimits(double forwardLimitPosition, + double reverseLimitPosition) override; + void DisableSoftPositionLimits() override; + void ConfigLimitMode(LimitMode mode) override; + void ConfigForwardLimit(double forwardLimitPosition) override; + void ConfigReverseLimit(double reverseLimitPosition) override; + void ConfigMaxOutputVoltage(double voltage) override; + void ConfigFaultTime(float faultTime) override; virtual void SetControlMode(ControlMode mode); virtual ControlMode GetControlMode() const; @@ -142,8 +142,8 @@ class CANJaguar : public MotorSafety, uint8_t GetDeviceID() const; // SpeedController overrides - virtual void SetInverted(bool isInverted) override; - virtual bool GetInverted() const override; + void SetInverted(bool isInverted) override; + bool GetInverted() const override; protected: // Control mode helpers diff --git a/wpilibc/athena/include/CANTalon.h b/wpilibc/athena/include/CANTalon.h index 6d57f94cd3..dc55278915 100644 --- a/wpilibc/athena/include/CANTalon.h +++ b/wpilibc/athena/include/CANTalon.h @@ -226,47 +226,47 @@ class CANTalon : public MotorSafety, virtual ~CANTalon(); // PIDOutput interface - virtual void PIDWrite(float output) override; + void PIDWrite(float output) override; // PIDSource interface - virtual double PIDGet() override; + double PIDGet() override; // MotorSafety interface - virtual void SetExpiration(float timeout) override; - virtual float GetExpiration() const override; - virtual bool IsAlive() const override; - virtual void StopMotor() override; - virtual void SetSafetyEnabled(bool enabled) override; - virtual bool IsSafetyEnabled() const override; - virtual void GetDescription(std::ostringstream& desc) const override; + void SetExpiration(float timeout) override; + float GetExpiration() const override; + bool IsAlive() const override; + void StopMotor() override; + void SetSafetyEnabled(bool enabled) override; + bool IsSafetyEnabled() const override; + void GetDescription(std::ostringstream& desc) const override; // CANSpeedController interface - virtual float Get() const override; - virtual void Set(float value) override; - virtual void Reset() override; - virtual void SetSetpoint(float value) override; - virtual void Disable() override; + float Get() const override; + void Set(float value) override; + void Reset() override; + void SetSetpoint(float value) override; + void Disable() override; virtual void EnableControl(); - virtual void Enable() override; - virtual void SetP(double p) override; - virtual void SetI(double i) override; - virtual void SetD(double d) override; + void Enable() override; + void SetP(double p) override; + void SetI(double i) override; + void SetD(double d) override; void SetF(double f); void SetIzone(unsigned iz); - virtual void SetPID(double p, double i, double d) override; + void SetPID(double p, double i, double d) override; virtual void SetPID(double p, double i, double d, double f); - virtual double GetP() const override; - virtual double GetI() const override; - virtual double GetD() const override; + double GetP() const override; + double GetI() const override; + double GetD() const override; virtual double GetF() const; - virtual bool IsModePID(CANSpeedController::ControlMode mode) const override; - virtual float GetBusVoltage() const override; - virtual float GetOutputVoltage() const override; - virtual float GetOutputCurrent() const override; - virtual float GetTemperature() const override; + bool IsModePID(CANSpeedController::ControlMode mode) const override; + float GetBusVoltage() const override; + float GetOutputVoltage() const override; + float GetOutputCurrent() const override; + float GetTemperature() const override; void SetPosition(double pos); - virtual double GetPosition() const override; - virtual double GetSpeed() const override; + double GetPosition() const override; + double GetSpeed() const override; virtual int GetClosedLoopError() const; virtual void SetAllowableClosedLoopErr(uint32_t allowableCloseLoopError); virtual int GetAnalogIn() const; @@ -290,23 +290,23 @@ class CANTalon : public MotorSafety, virtual int GetPulseWidthRiseToRiseUs() const; virtual FeedbackDeviceStatus IsSensorPresent( FeedbackDevice feedbackDevice) const; - virtual bool GetForwardLimitOK() const override; - virtual bool GetReverseLimitOK() const override; - virtual uint16_t GetFaults() const override; + bool GetForwardLimitOK() const override; + bool GetReverseLimitOK() const override; + uint16_t GetFaults() const override; uint16_t GetStickyFaults() const; void ClearStickyFaults(); - virtual void SetVoltageRampRate(double rampRate) override; + void SetVoltageRampRate(double rampRate) override; virtual void SetVoltageCompensationRampRate(double rampRate); - virtual uint32_t GetFirmwareVersion() const override; - virtual void ConfigNeutralMode(NeutralMode mode) override; - virtual void ConfigEncoderCodesPerRev(uint16_t codesPerRev) override; - virtual void ConfigPotentiometerTurns(uint16_t turns) override; - virtual void ConfigSoftPositionLimits(double forwardLimitPosition, - double reverseLimitPosition) override; - virtual void DisableSoftPositionLimits() override; - virtual void ConfigLimitMode(LimitMode mode) override; - virtual void ConfigForwardLimit(double forwardLimitPosition) override; - virtual void ConfigReverseLimit(double reverseLimitPosition) override; + uint32_t GetFirmwareVersion() const override; + void ConfigNeutralMode(NeutralMode mode) override; + void ConfigEncoderCodesPerRev(uint16_t codesPerRev) override; + void ConfigPotentiometerTurns(uint16_t turns) override; + void ConfigSoftPositionLimits(double forwardLimitPosition, + double reverseLimitPosition) override; + void DisableSoftPositionLimits() override; + void ConfigLimitMode(LimitMode mode) override; + void ConfigForwardLimit(double forwardLimitPosition) override; + void ConfigReverseLimit(double reverseLimitPosition) override; void ConfigLimitSwitchOverrides(bool bForwardLimitSwitchEn, bool bReverseLimitSwitchEn); void ConfigForwardSoftLimitEnable(bool bForwardSoftLimitEn); @@ -333,7 +333,7 @@ class CANTalon : public MotorSafety, * @param normallyOpen true for normally open. false for normally closed. */ void ConfigRevLimitSwitchNormallyOpen(bool normallyOpen); - virtual void ConfigMaxOutputVoltage(double voltage) override; + void ConfigMaxOutputVoltage(double voltage) override; void ConfigPeakOutputVoltage(double forwardVoltage, double reverseVoltage); void ConfigNominalOutputVoltage(double forwardVoltage, double reverseVoltage); /** @@ -349,7 +349,7 @@ class CANTalon : public MotorSafety, void ConfigSetParameter(uint32_t paramEnum, double value); bool GetParameter(uint32_t paramEnum, double& dvalue) const; - virtual void ConfigFaultTime(float faultTime) override; + void ConfigFaultTime(float faultTime) override; virtual void SetControlMode(ControlMode mode); void SetFeedbackDevice(FeedbackDevice device); void SetStatusFrameRateMs(StatusFrameRate stateFrame, int periodMs); @@ -449,8 +449,8 @@ class CANTalon : public MotorSafety, std::shared_ptr GetTable() const override; // SpeedController overrides - virtual void SetInverted(bool isInverted) override; - virtual bool GetInverted() const override; + void SetInverted(bool isInverted) override; + bool GetInverted() const override; private: // Values for various modes as is sent in the CAN packets for the Talon. diff --git a/wpilibc/athena/include/Counter.h b/wpilibc/athena/include/Counter.h index 8ac7f67898..2312bee6d5 100644 --- a/wpilibc/athena/include/Counter.h +++ b/wpilibc/athena/include/Counter.h @@ -94,7 +94,7 @@ class Counter : public SensorBase, void UpdateTable() override; void StartLiveWindowMode() override; void StopLiveWindowMode() override; - virtual std::string GetSmartDashboardType() const override; + std::string GetSmartDashboardType() const override; void InitTable(std::shared_ptr subTable) override; std::shared_ptr GetTable() const override; diff --git a/wpilibc/athena/include/DigitalInput.h b/wpilibc/athena/include/DigitalInput.h index b1f7a08db7..aca510b3b1 100644 --- a/wpilibc/athena/include/DigitalInput.h +++ b/wpilibc/athena/include/DigitalInput.h @@ -32,9 +32,9 @@ class DigitalInput : public DigitalSource, public LiveWindowSendable { uint32_t GetChannel() const override; // Digital Source Interface - virtual HAL_Handle GetPortHandleForRouting() const override; - virtual AnalogTriggerType GetAnalogTriggerTypeForRouting() const override; - virtual bool IsAnalogTrigger() const override; + HAL_Handle GetPortHandleForRouting() const override; + AnalogTriggerType GetAnalogTriggerTypeForRouting() const override; + bool IsAnalogTrigger() const override; void UpdateTable(); void StartLiveWindowMode(); diff --git a/wpilibc/athena/include/DigitalOutput.h b/wpilibc/athena/include/DigitalOutput.h index 8680c2a10e..c063a0371f 100644 --- a/wpilibc/athena/include/DigitalOutput.h +++ b/wpilibc/athena/include/DigitalOutput.h @@ -36,12 +36,12 @@ class DigitalOutput : public DigitalSource, void UpdateDutyCycle(float dutyCycle); // Digital Source Interface - virtual HAL_Handle GetPortHandleForRouting() const override; - virtual AnalogTriggerType GetAnalogTriggerTypeForRouting() const override; - virtual bool IsAnalogTrigger() const override; + HAL_Handle GetPortHandleForRouting() const override; + AnalogTriggerType GetAnalogTriggerTypeForRouting() const override; + bool IsAnalogTrigger() const override; - virtual void ValueChanged(ITable* source, llvm::StringRef key, - std::shared_ptr value, bool isNew); + void ValueChanged(ITable* source, llvm::StringRef key, + std::shared_ptr value, bool isNew) override; void UpdateTable(); void StartLiveWindowMode(); void StopLiveWindowMode(); diff --git a/wpilibc/athena/include/GearTooth.h b/wpilibc/athena/include/GearTooth.h index 73c3ceb893..41a0ea2ab6 100644 --- a/wpilibc/athena/include/GearTooth.h +++ b/wpilibc/athena/include/GearTooth.h @@ -21,12 +21,12 @@ class GearTooth : public Counter { public: /// 55 uSec for threshold static constexpr double kGearToothThreshold = 55e-6; - GearTooth(uint32_t channel, bool directionSensitive = false); - GearTooth(DigitalSource* source, bool directionSensitive = false); - GearTooth(std::shared_ptr source, - bool directionSensitive = false); + explicit GearTooth(uint32_t channel, bool directionSensitive = false); + explicit GearTooth(DigitalSource* source, bool directionSensitive = false); + explicit GearTooth(std::shared_ptr source, + bool directionSensitive = false); virtual ~GearTooth() = default; void EnableDirectionSensing(bool directionSensitive); - virtual std::string GetSmartDashboardType() const override; + std::string GetSmartDashboardType() const override; }; diff --git a/wpilibc/athena/include/Joystick.h b/wpilibc/athena/include/Joystick.h index 5c6f1fba40..36d557a593 100644 --- a/wpilibc/athena/include/Joystick.h +++ b/wpilibc/athena/include/Joystick.h @@ -72,19 +72,19 @@ class Joystick : public GenericHID, public ErrorBase { uint32_t GetAxisChannel(AxisType axis) const; void SetAxisChannel(AxisType axis, uint32_t channel); - virtual float GetX(JoystickHand hand = kRightHand) const override; - virtual float GetY(JoystickHand hand = kRightHand) const override; - virtual float GetZ() const override; - virtual float GetTwist() const override; - virtual float GetThrottle() const override; + float GetX(JoystickHand hand = kRightHand) const override; + float GetY(JoystickHand hand = kRightHand) const override; + float GetZ() const override; + float GetTwist() const override; + float GetThrottle() const override; virtual float GetAxis(AxisType axis) const; float GetRawAxis(uint32_t axis) const override; - virtual bool GetTrigger(JoystickHand hand = kRightHand) const override; - virtual bool GetTop(JoystickHand hand = kRightHand) const override; - virtual bool GetBumper(JoystickHand hand = kRightHand) const override; - virtual bool GetRawButton(uint32_t button) const override; - virtual int GetPOV(uint32_t pov = 0) 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 GetButton(ButtonType button) const; static Joystick* GetStickForPort(uint32_t port); diff --git a/wpilibc/athena/include/MotorSafetyHelper.h b/wpilibc/athena/include/MotorSafetyHelper.h index 60cd4c3b4f..9bb33d3f66 100644 --- a/wpilibc/athena/include/MotorSafetyHelper.h +++ b/wpilibc/athena/include/MotorSafetyHelper.h @@ -16,7 +16,7 @@ class MotorSafety; class MotorSafetyHelper : public ErrorBase { public: - MotorSafetyHelper(MotorSafety* safeObject); + explicit MotorSafetyHelper(MotorSafety* safeObject); ~MotorSafetyHelper(); void Feed(); void SetExpiration(float expirationTime); diff --git a/wpilibc/athena/include/PWM.h b/wpilibc/athena/include/PWM.h index ca6d53308b..8c6c3a5eaf 100644 --- a/wpilibc/athena/include/PWM.h +++ b/wpilibc/athena/include/PWM.h @@ -43,8 +43,8 @@ class PWM : public SensorBase, explicit PWM(uint32_t channel); virtual ~PWM(); - virtual void SetRaw(unsigned short value); - virtual unsigned short GetRaw() const; + virtual void SetRaw(uint16_t value); + virtual uint16_t GetRaw() const; virtual void SetPosition(float pos); virtual float GetPosition() const; virtual void SetSpeed(float speed); diff --git a/wpilibc/athena/include/PWMSpeedController.h b/wpilibc/athena/include/PWMSpeedController.h index 92a92a62a8..96a9b52178 100644 --- a/wpilibc/athena/include/PWMSpeedController.h +++ b/wpilibc/athena/include/PWMSpeedController.h @@ -16,15 +16,15 @@ class PWMSpeedController : public SafePWM, public SpeedController { public: virtual ~PWMSpeedController() = default; - virtual void Set(float value) override; - virtual float Get() const override; - virtual void Disable() override; - virtual void StopMotor() override; + void Set(float value) override; + float Get() const override; + void Disable() override; + void StopMotor() override; - virtual void PIDWrite(float output) override; + void PIDWrite(float output) override; - virtual void SetInverted(bool isInverted) override; - virtual bool GetInverted() const override; + void SetInverted(bool isInverted) override; + bool GetInverted() const override; protected: explicit PWMSpeedController(uint32_t channel); diff --git a/wpilibc/athena/include/PowerDistributionPanel.h b/wpilibc/athena/include/PowerDistributionPanel.h index fc8c4de9fc..70239aa9f6 100644 --- a/wpilibc/athena/include/PowerDistributionPanel.h +++ b/wpilibc/athena/include/PowerDistributionPanel.h @@ -19,7 +19,7 @@ class PowerDistributionPanel : public SensorBase, public LiveWindowSendable { public: PowerDistributionPanel(); - PowerDistributionPanel(uint8_t module); + explicit PowerDistributionPanel(uint8_t module); double GetVoltage() const; double GetTemperature() const; diff --git a/wpilibc/athena/include/Relay.h b/wpilibc/athena/include/Relay.h index 69647f82f3..aa253498fb 100644 --- a/wpilibc/athena/include/Relay.h +++ b/wpilibc/athena/include/Relay.h @@ -37,7 +37,7 @@ class Relay : public MotorSafety, enum Value { kOff, kOn, kForward, kReverse }; enum Direction { kBothDirections, kForwardOnly, kReverseOnly }; - Relay(uint32_t channel, Direction direction = kBothDirections); + explicit Relay(uint32_t channel, Direction direction = kBothDirections); virtual ~Relay(); void Set(Value value); diff --git a/wpilibc/athena/include/SPI.h b/wpilibc/athena/include/SPI.h index 3b05e997b7..338521d6a7 100644 --- a/wpilibc/athena/include/SPI.h +++ b/wpilibc/athena/include/SPI.h @@ -22,7 +22,7 @@ class DigitalInput; class SPI : public SensorBase { public: enum Port { kOnboardCS0, kOnboardCS1, kOnboardCS2, kOnboardCS3, kMXP }; - SPI(Port SPIport); + explicit SPI(Port SPIport); virtual ~SPI(); SPI(const SPI&) = delete; diff --git a/wpilibc/athena/include/SolenoidBase.h b/wpilibc/athena/include/SolenoidBase.h index 608511666a..5585645c0d 100644 --- a/wpilibc/athena/include/SolenoidBase.h +++ b/wpilibc/athena/include/SolenoidBase.h @@ -27,8 +27,8 @@ class SolenoidBase : public SensorBase { protected: explicit SolenoidBase(uint8_t pcmID); - const static int m_maxModules = 63; - const static int m_maxPorts = 8; + 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. diff --git a/wpilibc/athena/include/Vision/ColorImage.h b/wpilibc/athena/include/Vision/ColorImage.h index 96346ec803..d9cbabe3aa 100644 --- a/wpilibc/athena/include/Vision/ColorImage.h +++ b/wpilibc/athena/include/Vision/ColorImage.h @@ -13,7 +13,7 @@ class ColorImage : public ImageBase { public: - ColorImage(ImageType type); + explicit ColorImage(ImageType type); virtual ~ColorImage() = default; BinaryImage* ThresholdRGB(int redLow, int redHigh, int greenLow, int greenHigh, int blueLow, int blueHigh); diff --git a/wpilibc/athena/include/Vision/HSLImage.h b/wpilibc/athena/include/Vision/HSLImage.h index f94972e40e..190eb0568e 100644 --- a/wpilibc/athena/include/Vision/HSLImage.h +++ b/wpilibc/athena/include/Vision/HSLImage.h @@ -15,6 +15,6 @@ class HSLImage : public ColorImage { public: HSLImage(); - HSLImage(const char* fileName); + explicit HSLImage(const char* fileName); virtual ~HSLImage() = default; }; diff --git a/wpilibc/athena/include/Vision/ImageBase.h b/wpilibc/athena/include/Vision/ImageBase.h index d128632079..e6525e686d 100644 --- a/wpilibc/athena/include/Vision/ImageBase.h +++ b/wpilibc/athena/include/Vision/ImageBase.h @@ -14,7 +14,7 @@ class ImageBase : public ErrorBase { public: - ImageBase(ImageType type); + explicit ImageBase(ImageType type); virtual ~ImageBase(); virtual void Write(const char* fileName); int GetHeight(); diff --git a/wpilibc/athena/include/Vision/RGBImage.h b/wpilibc/athena/include/Vision/RGBImage.h index 37da9bd4cc..c59b1eb627 100644 --- a/wpilibc/athena/include/Vision/RGBImage.h +++ b/wpilibc/athena/include/Vision/RGBImage.h @@ -15,6 +15,6 @@ class RGBImage : public ColorImage { public: RGBImage(); - RGBImage(const char* fileName); + explicit RGBImage(const char* fileName); virtual ~RGBImage() = default; }; diff --git a/wpilibc/athena/src/ADXL345_I2C.cpp b/wpilibc/athena/src/ADXL345_I2C.cpp index fcbeec3062..8d2b1d6f3a 100644 --- a/wpilibc/athena/src/ADXL345_I2C.cpp +++ b/wpilibc/athena/src/ADXL345_I2C.cpp @@ -53,8 +53,8 @@ double ADXL345_I2C::GetZ() { return GetAcceleration(kAxis_Z); } */ double ADXL345_I2C::GetAcceleration(ADXL345_I2C::Axes axis) { int16_t rawAccel = 0; - m_i2c.Read(kDataRegister + (uint8_t)axis, sizeof(rawAccel), - (uint8_t*)&rawAccel); + m_i2c.Read(kDataRegister + static_cast(axis), sizeof(rawAccel), + reinterpret_cast(&rawAccel)); return rawAccel * kGsPerLSB; } @@ -67,7 +67,8 @@ double ADXL345_I2C::GetAcceleration(ADXL345_I2C::Axes axis) { ADXL345_I2C::AllAxes ADXL345_I2C::GetAccelerations() { AllAxes data = AllAxes(); int16_t rawData[3]; - m_i2c.Read(kDataRegister, sizeof(rawData), (uint8_t*)rawData); + m_i2c.Read(kDataRegister, sizeof(rawData), + reinterpret_cast(rawData)); data.XAxis = rawData[0] * kGsPerLSB; data.YAxis = rawData[1] * kGsPerLSB; diff --git a/wpilibc/athena/src/ADXRS450_Gyro.cpp b/wpilibc/athena/src/ADXRS450_Gyro.cpp index 27be0d89aa..8d8c770186 100644 --- a/wpilibc/athena/src/ADXRS450_Gyro.cpp +++ b/wpilibc/athena/src/ADXRS450_Gyro.cpp @@ -133,8 +133,8 @@ void ADXRS450_Gyro::Reset() { m_spi.ResetAccumulator(); } * integration of the returned rate from the gyro. */ float ADXRS450_Gyro::GetAngle() const { - return (float)(m_spi.GetAccumulatorValue() * kDegreePerSecondPerLSB * - kSamplePeriod); + return static_cast(m_spi.GetAccumulatorValue() * + kDegreePerSecondPerLSB * kSamplePeriod); } /** @@ -145,5 +145,6 @@ float ADXRS450_Gyro::GetAngle() const { * @return the current rate in degrees per second */ double ADXRS450_Gyro::GetRate() const { - return (double)m_spi.GetAccumulatorLastValue() * kDegreePerSecondPerLSB; + return static_cast(m_spi.GetAccumulatorLastValue()) * + kDegreePerSecondPerLSB; } diff --git a/wpilibc/athena/src/CANJaguar.cpp b/wpilibc/athena/src/CANJaguar.cpp index eacddc0f3c..e3961f774a 100644 --- a/wpilibc/athena/src/CANJaguar.cpp +++ b/wpilibc/athena/src/CANJaguar.cpp @@ -343,58 +343,58 @@ void CANJaguar::PIDWrite(float output) { } uint8_t CANJaguar::packPercentage(uint8_t* buffer, double value) { - int16_t intValue = (int16_t)(value * 32767.0); - *((int16_t*)buffer) = swap16(intValue); + 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) { - int16_t intValue = (int16_t)(value * 256.0); - *((int16_t*)buffer) = swap16(intValue); + 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 = (int32_t)(value * 65536.0); - *((int32_t*)buffer) = swap32(intValue); + int32_t 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) { - *((int16_t*)buffer) = swap16(value); + *reinterpret_cast(buffer) = swap16(value); return sizeof(int16_t); } uint8_t CANJaguar::packint32_t(uint8_t* buffer, int32_t value) { - *((int32_t*)buffer) = swap32(value); + *reinterpret_cast(buffer) = swap32(value); return sizeof(int32_t); } double CANJaguar::unpackPercentage(uint8_t* buffer) const { - int16_t value = *((int16_t*)buffer); + int16_t value = *reinterpret_cast(buffer); value = swap16(value); return value / 32767.0; } double CANJaguar::unpackFXP8_8(uint8_t* buffer) const { - int16_t value = *((int16_t*)buffer); + int16_t value = *reinterpret_cast(buffer); value = swap16(value); return value / 256.0; } double CANJaguar::unpackFXP16_16(uint8_t* buffer) const { - int32_t value = *((int32_t*)buffer); + int32_t value = *reinterpret_cast(buffer); value = swap32(value); return value / 65536.0; } int16_t CANJaguar::unpackint16_t(uint8_t* buffer) const { - int16_t value = *((int16_t*)buffer); + int16_t value = *reinterpret_cast(buffer); return swap16(value); } int32_t CANJaguar::unpackint32_t(uint8_t* buffer) const { - int32_t value = *((int32_t*)buffer); + int32_t value = *reinterpret_cast(buffer); return swap32(value); } @@ -552,7 +552,7 @@ void CANJaguar::verify() { // If the Jaguar lost power, everything should be considered unverified. if (getMessage(LM_API_STATUS_POWER, CAN_MSGID_FULL_M, dataBuffer, &dataSize)) { - bool powerCycled = (bool)dataBuffer[0]; + bool powerCycled = static_cast(dataBuffer[0]); if (powerCycled) { // Clear the power cycled bit @@ -667,13 +667,13 @@ void CANJaguar::verify() { if (!m_pVerified) { uint32_t message = 0; - if (m_controlMode == kSpeed) + if (m_controlMode == kSpeed) { message = LM_API_SPD_PC; - else if (m_controlMode == kPosition) + } else if (m_controlMode == kPosition) { message = LM_API_POS_PC; - else if (m_controlMode == kCurrent) + } else if (m_controlMode == kCurrent) { message = LM_API_ICTRL_PC; - else { + } else { wpi_setWPIErrorWithContext( IncompatibleMode, "PID constants only apply in Speed, Position, and Current mode"); @@ -697,13 +697,13 @@ void CANJaguar::verify() { if (!m_iVerified) { uint32_t message = 0; - if (m_controlMode == kSpeed) + if (m_controlMode == kSpeed) { message = LM_API_SPD_IC; - else if (m_controlMode == kPosition) + } else if (m_controlMode == kPosition) { message = LM_API_POS_IC; - else if (m_controlMode == kCurrent) + } else if (m_controlMode == kCurrent) { message = LM_API_ICTRL_IC; - else { + } else { wpi_setWPIErrorWithContext( IncompatibleMode, "PID constants only apply in Speed, Position, and Current mode"); @@ -727,13 +727,13 @@ void CANJaguar::verify() { if (!m_dVerified) { uint32_t message = 0; - if (m_controlMode == kSpeed) + if (m_controlMode == kSpeed) { message = LM_API_SPD_DC; - else if (m_controlMode == kPosition) + } else if (m_controlMode == kPosition) { message = LM_API_POS_DC; - else if (m_controlMode == kCurrent) + } else if (m_controlMode == kCurrent) { message = LM_API_ICTRL_DC; - else { + } else { wpi_setWPIErrorWithContext( IncompatibleMode, "PID constants only apply in Speed, Position, and Current mode"); @@ -807,9 +807,9 @@ void CANJaguar::verify() { &dataSize)) { LimitMode mode = (LimitMode)dataBuffer[0]; - if (mode == m_limitMode) + if (mode == m_limitMode) { m_limitModeVerified = true; - else { + } else { // It's wrong - set it again ConfigLimitMode(m_limitMode); } @@ -824,9 +824,9 @@ void CANJaguar::verify() { &dataSize)) { double limit = unpackFXP16_16(dataBuffer); - if (FXP16_EQ(limit, m_forwardLimit)) + if (FXP16_EQ(limit, m_forwardLimit)) { m_forwardLimitVerified = true; - else { + } else { // It's wrong - set it again ConfigForwardLimit(m_forwardLimit); } @@ -841,9 +841,9 @@ void CANJaguar::verify() { &dataSize)) { double limit = unpackFXP16_16(dataBuffer); - if (FXP16_EQ(limit, m_reverseLimit)) + if (FXP16_EQ(limit, m_reverseLimit)) { m_reverseLimitVerified = true; - else { + } else { // It's wrong - set it again ConfigReverseLimit(m_reverseLimit); } @@ -861,9 +861,9 @@ void CANJaguar::verify() { // The returned max output voltage is sometimes slightly higher or // lower than what was sent. This should not trigger resending // the message. - if (std::abs(voltage - m_maxOutputVoltage) < 0.1) + if (std::abs(voltage - m_maxOutputVoltage) < 0.1) { m_maxOutputVoltageVerified = true; - else { + } else { // It's wrong - set it again ConfigMaxOutputVoltage(m_maxOutputVoltage); } @@ -879,9 +879,9 @@ void CANJaguar::verify() { &dataSize)) { double rate = unpackPercentage(dataBuffer); - if (FXP16_EQ(rate, m_voltageRampRate)) + if (FXP16_EQ(rate, m_voltageRampRate)) { m_voltageRampRateVerified = true; - else { + } else { // It's wrong - set it again SetVoltageRampRate(m_voltageRampRate); } @@ -894,9 +894,9 @@ void CANJaguar::verify() { &dataSize)) { double rate = unpackFXP8_8(dataBuffer); - if (FXP8_EQ(rate, m_voltageRampRate)) + if (FXP8_EQ(rate, m_voltageRampRate)) { m_voltageRampRateVerified = true; - else { + } else { // It's wrong - set it again SetVoltageRampRate(m_voltageRampRate); } @@ -912,9 +912,9 @@ void CANJaguar::verify() { &dataSize)) { uint16_t faultTime = unpackint16_t(dataBuffer); - if ((uint16_t)(m_faultTime * 1000.0) == faultTime) + if ((uint16_t)(m_faultTime * 1000.0) == faultTime) { m_faultTimeVerified = true; - else { + } else { // It's wrong - set it again ConfigFaultTime(m_faultTime); } diff --git a/wpilibc/athena/src/CANTalon.cpp b/wpilibc/athena/src/CANTalon.cpp index 9c3b9fc969..a7f920b88b 100644 --- a/wpilibc/athena/src/CANTalon.cpp +++ b/wpilibc/athena/src/CANTalon.cpp @@ -119,7 +119,7 @@ float CANTalon::Get() const { case kFollower: default: m_impl->GetAppliedThrottle(value); - return (float)value / 1023.0; + return static_cast(value) / 1023.0; } } @@ -156,11 +156,11 @@ void CANTalon::Set(float value) { status = CTR_OKAY; } break; case CANSpeedController::kFollower: { - status = m_impl->SetDemand((int)value); + status = m_impl->SetDemand(static_cast(value)); } break; case CANSpeedController::kVoltage: { // Voltage is an 8.8 fixed point number. - int volts = int((m_isInverted ? -value : value) * 256); + int volts = static_cast((m_isInverted ? -value : value) * 256); status = m_impl->SetDemand(volts); } break; case CANSpeedController::kSpeed: @@ -177,7 +177,7 @@ void CANTalon::Set(float value) { status = m_impl->SetDemand(milliamperes); } break; case CANSpeedController::kMotionProfile: { - status = m_impl->SetDemand((int)value); + status = m_impl->SetDemand(static_cast(value)); } break; default: wpi_setWPIErrorWithContext( @@ -216,7 +216,7 @@ void CANTalon::Reset() { * for more information). */ void CANTalon::Disable() { - m_impl->SetModeSelect((int)CANTalon::kDisabled); + m_impl->SetModeSelect(static_cast(CANTalon::kDisabled)); m_controlEnabled = false; } @@ -358,7 +358,8 @@ void CANTalon::SetFeedbackDevice(FeedbackDevice feedbackDevice) { */ m_feedbackDevice = feedbackDevice; /* pass feedback to actual CAN frame */ - CTR_Code status = m_impl->SetFeedbackDeviceSelect((int)feedbackDevice); + CTR_Code status = + m_impl->SetFeedbackDeviceSelect(static_cast(feedbackDevice)); if (status != CTR_OKAY) { wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); } @@ -368,7 +369,8 @@ void CANTalon::SetFeedbackDevice(FeedbackDevice feedbackDevice) { * Select the feedback device to use in closed-loop */ void CANTalon::SetStatusFrameRateMs(StatusFrameRate stateFrame, int periodMs) { - CTR_Code status = m_impl->SetStatusFrameRate((int)stateFrame, periodMs); + CTR_Code status = + m_impl->SetStatusFrameRate(static_cast(stateFrame), periodMs); if (status != CTR_OKAY) { wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); } @@ -518,7 +520,7 @@ float CANTalon::GetBusVoltage() const { float CANTalon::GetOutputVoltage() const { int throttle11; CTR_Code status = m_impl->GetAppliedThrottle(throttle11); - float voltage = GetBusVoltage() * (float(throttle11) / 1023.0); + float voltage = GetBusVoltage() * (static_cast(throttle11) / 1023.0); if (status != CTR_OKAY) { wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); } @@ -1086,7 +1088,8 @@ void CANTalon::SetVoltageRampRate(double rampRate) { Talon's throttle ramp is in dThrot/d10ms. 1023 is full fwd, -1023 is full rev. */ double rampRatedThrotPer10ms = (rampRate * 1023.0 / 12.0) / 100; - CTR_Code status = m_impl->SetRampThrottle((int)rampRatedThrotPer10ms); + CTR_Code status = + m_impl->SetRampThrottle(static_cast(rampRatedThrotPer10ms)); if (status != CTR_OKAY) { wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); } @@ -1180,8 +1183,8 @@ void CANTalon::ConfigNeutralMode(NeutralMode mode) { CTR_Code status = CTR_OKAY; switch (mode) { default: - case kNeutralMode_Jumper: /* use default setting in flash based on - webdash/BrakeCal button selection */ + case kNeutralMode_Jumper: + // use default setting in flash based on webdash/BrakeCal button selection status = m_impl->SetOverrideBrakeType( CanTalonSRX::kBrakeOverride_UseDefaultsFromFlash); break; @@ -1347,8 +1350,9 @@ void CANTalon::ConfigLimitMode(LimitMode mode) { } break; - case kLimitMode_SrxDisableSwitchInputs: /** disable both limit switches and - soft limits */ + case kLimitMode_SrxDisableSwitchInputs: + // disable both limit switches and soft limits + /* turn on both limits. SRX has individual enables and polarity for each * limit switch.*/ status = m_impl->SetForwardSoftEnable(false); @@ -1586,7 +1590,7 @@ void CANTalon::ApplyControlMode(CANSpeedController::ControlMode mode) { break; } // Keep the talon disabled until Set() is called. - CTR_Code status = m_impl->SetModeSelect((int)kDisabled); + CTR_Code status = m_impl->SetModeSelect(static_cast(kDisabled)); if (status != CTR_OKAY) { wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); } @@ -1647,14 +1651,13 @@ double CANTalon::GetNativeUnitsPerRotationScalar( CTR_Code status = CTR_OKAY; double retval = 0; switch (devToLookup) { - case QuadEncoder: { /* When caller wants to lookup Quadrature, the QEI may - * be in 1x if the selected feedback is edge counter. - * Additionally if the quadrature source is the CTRE Mag - * encoder, then the CPR is known. - * This is nice in that the calling app does not require - * knowing the CPR at all. - * So do both checks here. - */ + case QuadEncoder: { + /* When caller wants to lookup Quadrature, the QEI may be in 1x if the + * selected feedback is edge counter. Additionally if the quadrature + * source is the CTRE Mag encoder, then the CPR is known. This is nice in + * that the calling app does not require knowing the CPR at all. So do + * both checks here. + */ int32_t qeiPulsePerCount = 4; /* default to 4x */ switch (m_feedbackDevice) { case CtreMagEncoder_Relative: @@ -1669,8 +1672,8 @@ double CANTalon::GetNativeUnitsPerRotationScalar( qeiPulsePerCount = 1; break; case QuadEncoder: /* Talon's QEI is 4x */ - default: /* pulse width and everything else, assume its regular quad - use. */ + default: + // pulse width and everything else, assume its regular quad use. break; } if (scalingAvail) { @@ -1710,7 +1713,8 @@ double CANTalon::GetNativeUnitsPerRotationScalar( * bottom of this func. */ } else { - retval = (double)kNativeAdcUnitsPerRotation / m_numPotTurns; + retval = + static_cast(kNativeAdcUnitsPerRotation) / m_numPotTurns; scalingAvail = true; } break; @@ -1746,11 +1750,11 @@ double CANTalon::GetNativeUnitsPerRotationScalar( int32_t CANTalon::ScaleRotationsToNativeUnits(FeedbackDevice devToLookup, double fullRotations) const { /* first assume we don't have config info, prep the default return */ - int32_t retval = (int32_t)fullRotations; + int32_t retval = static_cast(fullRotations); /* retrieve scaling info */ double scalar = GetNativeUnitsPerRotationScalar(devToLookup); /* apply scalar if its available */ - if (scalar > 0) retval = (int32_t)(fullRotations * scalar); + if (scalar > 0) retval = static_cast(fullRotations * scalar); return retval; } @@ -1768,11 +1772,13 @@ int32_t CANTalon::ScaleRotationsToNativeUnits(FeedbackDevice devToLookup, int32_t CANTalon::ScaleVelocityToNativeUnits(FeedbackDevice devToLookup, double rpm) const { /* first assume we don't have config info, prep the default return */ - int32_t retval = (int32_t)rpm; + int32_t retval = static_cast(rpm); /* retrieve scaling info */ double scalar = GetNativeUnitsPerRotationScalar(devToLookup); /* apply scalar if its available */ - if (scalar > 0) retval = (int32_t)(rpm * kMinutesPer100msUnit * scalar); + if (scalar > 0) { + retval = static_cast(rpm * kMinutesPer100msUnit * scalar); + } return retval; } @@ -1789,11 +1795,11 @@ int32_t CANTalon::ScaleVelocityToNativeUnits(FeedbackDevice devToLookup, double CANTalon::ScaleNativeUnitsToRotations(FeedbackDevice devToLookup, int32_t nativePos) const { /* first assume we don't have config info, prep the default return */ - double retval = (double)nativePos; + double retval = static_cast(nativePos); /* retrieve scaling info */ double scalar = GetNativeUnitsPerRotationScalar(devToLookup); /* apply scalar if its available */ - if (scalar > 0) retval = ((double)nativePos) / scalar; + if (scalar > 0) retval = static_cast(nativePos) / scalar; return retval; } @@ -1810,12 +1816,12 @@ double CANTalon::ScaleNativeUnitsToRotations(FeedbackDevice devToLookup, double CANTalon::ScaleNativeUnitsToRpm(FeedbackDevice devToLookup, int32_t nativeVel) const { /* first assume we don't have config info, prep the default return */ - double retval = (double)nativeVel; + double retval = static_cast(nativeVel); /* retrieve scaling info */ double scalar = GetNativeUnitsPerRotationScalar(devToLookup); /* apply scalar if its available */ if (scalar > 0) - retval = (double)(nativeVel) / (scalar * kMinutesPer100msUnit); + retval = static_cast(nativeVel) / (scalar * kMinutesPer100msUnit); return retval; } diff --git a/wpilibc/athena/src/CameraServer.cpp b/wpilibc/athena/src/CameraServer.cpp index dfb8e950e9..bbafe58fb5 100644 --- a/wpilibc/athena/src/CameraServer.cpp +++ b/wpilibc/athena/src/CameraServer.cpp @@ -41,9 +41,9 @@ CameraServer::CameraServer() void CameraServer::FreeImageData( std::tuple imageData) { - if (std::get<3>(imageData)) + if (std::get<3>(imageData)) { imaqDispose(std::get<0>(imageData)); - else if (std::get<0>(imageData) != nullptr) { + } else if (std::get<0>(imageData) != nullptr) { std::lock_guard lock(m_imageMutex); m_dataPool.push_back(std::get<0>(imageData)); } @@ -59,9 +59,9 @@ void CameraServer::SetImageData(uint8_t* data, unsigned int size, void CameraServer::SetImage(Image const* image) { unsigned int dataSize = 0; - uint8_t* data = - (uint8_t*)imaqFlatten(image, IMAQ_FLATTEN_IMAGE, IMAQ_COMPRESSION_JPEG, - 10 * m_quality, &dataSize); + uint8_t* data = reinterpret_cast( + imaqFlatten(image, IMAQ_FLATTEN_IMAGE, IMAQ_COMPRESSION_JPEG, + 10 * m_quality, &dataSize)); // If we're using a HW camera, then find the start of the data bool hwClient; diff --git a/wpilibc/athena/src/DriverStation.cpp b/wpilibc/athena/src/DriverStation.cpp index 2aac7c663b..9b8d134f11 100644 --- a/wpilibc/athena/src/DriverStation.cpp +++ b/wpilibc/athena/src/DriverStation.cpp @@ -210,7 +210,7 @@ int DriverStation::GetJoystickType(uint32_t stick) const { return -1; } std::lock_guard lock(m_joystickDataMutex); - return (int)m_joystickDescriptor[stick].type; + return static_cast(m_joystickDescriptor[stick].type); } /** @@ -225,7 +225,7 @@ bool DriverStation::GetJoystickIsXbox(uint32_t stick) const { return false; } std::lock_guard lock(m_joystickDataMutex); - return (bool)m_joystickDescriptor[stick].isXbox; + return static_cast(m_joystickDescriptor[stick].isXbox); } /** diff --git a/wpilibc/athena/src/Encoder.cpp b/wpilibc/athena/src/Encoder.cpp index 301473a4aa..4c500468a5 100644 --- a/wpilibc/athena/src/Encoder.cpp +++ b/wpilibc/athena/src/Encoder.cpp @@ -214,7 +214,6 @@ void Encoder::Reset() { int32_t status = 0; HAL_ResetEncoder(m_encoder, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); - ; } /** diff --git a/wpilibc/athena/src/PIDController.cpp b/wpilibc/athena/src/PIDController.cpp index 0cc3f7cc19..5ecc2b8fee 100644 --- a/wpilibc/athena/src/PIDController.cpp +++ b/wpilibc/athena/src/PIDController.cpp @@ -582,9 +582,9 @@ std::string PIDController::GetSmartDashboardType() const { return "PIDController"; } -void PIDController::InitTable(std::shared_ptr table) { +void PIDController::InitTable(std::shared_ptr subtable) { if (m_table != nullptr) m_table->RemoveTableListener(this); - m_table = table; + m_table = subtable; if (m_table != nullptr) { m_table->PutNumber(kP, GetP()); m_table->PutNumber(kI, GetI()); diff --git a/wpilibc/athena/src/PWM.cpp b/wpilibc/athena/src/PWM.cpp index 56e5e6e7df..ffa5c9042f 100644 --- a/wpilibc/athena/src/PWM.cpp +++ b/wpilibc/athena/src/PWM.cpp @@ -231,7 +231,7 @@ float PWM::GetSpeed() const { * * @param value Raw PWM value. */ -void PWM::SetRaw(unsigned short value) { +void PWM::SetRaw(uint16_t value) { if (StatusIsFatal()) return; int32_t status = 0; @@ -246,11 +246,11 @@ void PWM::SetRaw(unsigned short value) { * * @return Raw PWM control value. */ -unsigned short PWM::GetRaw() const { +uint16_t PWM::GetRaw() const { if (StatusIsFatal()) return 0; int32_t status = 0; - unsigned short value = HAL_GetPWMRaw(m_handle, &status); + uint16_t value = HAL_GetPWMRaw(m_handle, &status); wpi_setErrorWithContext(status, HAL_GetErrorMessage(status)); return value; diff --git a/wpilibc/athena/src/SPI.cpp b/wpilibc/athena/src/SPI.cpp index a0ec8f0663..016b131f5e 100644 --- a/wpilibc/athena/src/SPI.cpp +++ b/wpilibc/athena/src/SPI.cpp @@ -49,8 +49,9 @@ void SPI::SetClockRate(double hz) { HAL_SetSPISpeed(m_port, hz); } */ void SPI::SetMSBFirst() { m_msbFirst = true; - HAL_SetSPIOpts(m_port, (int)m_msbFirst, (int)m_sampleOnTrailing, - (int)m_clk_idle_high); + HAL_SetSPIOpts(m_port, static_cast(m_msbFirst), + static_cast(m_sampleOnTrailing), + static_cast(m_clk_idle_high)); } /** @@ -59,8 +60,9 @@ void SPI::SetMSBFirst() { */ void SPI::SetLSBFirst() { m_msbFirst = false; - HAL_SetSPIOpts(m_port, (int)m_msbFirst, (int)m_sampleOnTrailing, - (int)m_clk_idle_high); + HAL_SetSPIOpts(m_port, static_cast(m_msbFirst), + static_cast(m_sampleOnTrailing), + static_cast(m_clk_idle_high)); } /** @@ -69,8 +71,9 @@ void SPI::SetLSBFirst() { */ void SPI::SetSampleDataOnFalling() { m_sampleOnTrailing = true; - HAL_SetSPIOpts(m_port, (int)m_msbFirst, (int)m_sampleOnTrailing, - (int)m_clk_idle_high); + HAL_SetSPIOpts(m_port, static_cast(m_msbFirst), + static_cast(m_sampleOnTrailing), + static_cast(m_clk_idle_high)); } /** @@ -79,8 +82,9 @@ void SPI::SetSampleDataOnFalling() { */ void SPI::SetSampleDataOnRising() { m_sampleOnTrailing = false; - HAL_SetSPIOpts(m_port, (int)m_msbFirst, (int)m_sampleOnTrailing, - (int)m_clk_idle_high); + HAL_SetSPIOpts(m_port, static_cast(m_msbFirst), + static_cast(m_sampleOnTrailing), + static_cast(m_clk_idle_high)); } /** @@ -89,8 +93,9 @@ void SPI::SetSampleDataOnRising() { */ void SPI::SetClockActiveLow() { m_clk_idle_high = true; - HAL_SetSPIOpts(m_port, (int)m_msbFirst, (int)m_sampleOnTrailing, - (int)m_clk_idle_high); + HAL_SetSPIOpts(m_port, static_cast(m_msbFirst), + static_cast(m_sampleOnTrailing), + static_cast(m_clk_idle_high)); } /** @@ -99,8 +104,9 @@ void SPI::SetClockActiveLow() { */ void SPI::SetClockActiveHigh() { m_clk_idle_high = false; - HAL_SetSPIOpts(m_port, (int)m_msbFirst, (int)m_sampleOnTrailing, - (int)m_clk_idle_high); + HAL_SetSPIOpts(m_port, static_cast(m_msbFirst), + static_cast(m_sampleOnTrailing), + static_cast(m_clk_idle_high)); } /** @@ -153,8 +159,9 @@ int32_t SPI::Read(bool initiate, uint8_t* dataReceived, uint8_t size) { auto dataToSend = new uint8_t[size]; std::memset(dataToSend, 0, size); retVal = HAL_TransactionSPI(m_port, dataToSend, dataReceived, size); - } else + } else { retVal = HAL_ReadSPI(m_port, dataReceived, size); + } return retVal; } @@ -192,9 +199,9 @@ void SPI::InitAccumulator(double period, uint32_t cmd, uint8_t xfer_size, uint8_t data_shift, uint8_t data_size, bool is_signed, bool big_endian) { int32_t status = 0; - HAL_InitSPIAccumulator(m_port, (uint32_t)(period * 1e6), cmd, xfer_size, - valid_mask, valid_value, data_shift, data_size, - is_signed, big_endian, &status); + 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)); } diff --git a/wpilibc/athena/src/Servo.cpp b/wpilibc/athena/src/Servo.cpp index 9edc1b528d..68f99ff89f 100644 --- a/wpilibc/athena/src/Servo.cpp +++ b/wpilibc/athena/src/Servo.cpp @@ -83,7 +83,8 @@ void Servo::SetAngle(float degrees) { degrees = kMaxServoAngle; } - SetPosition(((float)(degrees - kMinServoAngle)) / GetServoAngleRange()); + SetPosition(static_cast(degrees - kMinServoAngle) / + GetServoAngleRange()); } /** @@ -95,7 +96,8 @@ void Servo::SetAngle(float degrees) { * @return The angle in degrees to which the servo is set. */ float Servo::GetAngle() const { - return (float)GetPosition() * GetServoAngleRange() + kMinServoAngle; + return static_cast(GetPosition()) * GetServoAngleRange() + + kMinServoAngle; } void Servo::ValueChanged(ITable* source, llvm::StringRef key, diff --git a/wpilibc/athena/src/USBCamera.cpp b/wpilibc/athena/src/USBCamera.cpp index 738d56adaa..22681b6f01 100644 --- a/wpilibc/athena/src/USBCamera.cpp +++ b/wpilibc/athena/src/USBCamera.cpp @@ -34,7 +34,7 @@ * the SOS flag explanation. */ unsigned int USBCamera::GetJpegSize(void* buffer, unsigned int buffSize) { - uint8_t* data = (uint8_t*)buffer; + uint8_t* data = static_cast(buffer); if (!wpi_assert(data[0] == 0xff && data[1] == 0xd8)) return 0; unsigned int pos = 2; while (pos < buffSize) { @@ -201,7 +201,8 @@ void USBCamera::UpdateSettings() { IMAQdxValueTypeF64, &minv); SAFE_IMAQ_CALL(IMAQdxGetAttributeMaximum, m_id, ATTR_EX_VALUE, IMAQdxValueTypeF64, &maxv); - double val = minv + ((maxv - minv) * ((double)m_exposureValue / 100.0)); + double val = + minv + (maxv - minv) * (static_cast(m_exposureValue) / 100.0); SAFE_IMAQ_CALL(IMAQdxSetAttribute, m_id, ATTR_EX_VALUE, IMAQdxValueTypeF64, val); } @@ -215,7 +216,8 @@ void USBCamera::UpdateSettings() { IMAQdxValueTypeF64, &minv); SAFE_IMAQ_CALL(IMAQdxGetAttributeMaximum, m_id, ATTR_BR_VALUE, IMAQdxValueTypeF64, &maxv); - double val = minv + ((maxv - minv) * ((double)m_brightness / 100.0)); + double val = + minv + (maxv - minv) * (static_cast(m_brightness) / 100.0); SAFE_IMAQ_CALL(IMAQdxSetAttribute, m_id, ATTR_BR_VALUE, IMAQdxValueTypeF64, val); diff --git a/wpilibc/athena/src/Vision/AxisCamera.cpp b/wpilibc/athena/src/Vision/AxisCamera.cpp index a8f9e8ebb9..d72532da25 100644 --- a/wpilibc/athena/src/Vision/AxisCamera.cpp +++ b/wpilibc/athena/src/Vision/AxisCamera.cpp @@ -133,9 +133,8 @@ int AxisCamera::CopyJPEG(char** destImage, unsigned int& destImageSize, if (m_imageData.size() == 0) return 0; // if no source image - if (destImageBufferSize < - m_imageData.size()) // if current destination buffer too small - { + // if current destination buffer too small + if (destImageBufferSize < m_imageData.size()) { if (*destImage != nullptr) delete[] * destImage; destImageBufferSize = m_imageData.size() + kImageBufferAllocationIncrement; *destImage = new char[destImageBufferSize]; @@ -148,7 +147,7 @@ int AxisCamera::CopyJPEG(char** destImage, unsigned int& destImageSize, std::copy(m_imageData.begin(), m_imageData.end(), *destImage); destImageSize = m_imageData.size(); - ; + return 1; } diff --git a/wpilibc/athena/src/Vision/BaeUtilities.cpp b/wpilibc/athena/src/Vision/BaeUtilities.cpp index 3d1f561021..609bf3625f 100644 --- a/wpilibc/athena/src/Vision/BaeUtilities.cpp +++ b/wpilibc/athena/src/Vision/BaeUtilities.cpp @@ -45,8 +45,7 @@ void SetDebugFlag(DebugOutputType flag) { dprintfFlag = flag; } * * @param tempString The format string. */ -void dprintf(const char* tempString, ...) /* Variable argument list */ -{ +void dprintf(const char* tempString, ...) { va_list args; /* Input argument list */ int line_number; /* Line number passed in argument */ int type; @@ -166,7 +165,7 @@ void dprintf(const char* tempString, ...) /* Variable argument list */ * @return The normalized position from -1 to +1 */ double RangeToNormalized(double position, int range) { - return (((position * 2.0) / (double)range) - 1.0); + return position * 2.0 / static_cast(range) - 1.0; } /** @@ -179,11 +178,11 @@ double RangeToNormalized(double position, int range) { */ float NormalizeToRange(float normalizedValue, float minRange, float maxRange) { float range = maxRange - minRange; - float temp = (float)((normalizedValue / 2.0) + 0.5) * range; + float temp = static_cast(normalizedValue / 2.0 + 0.5) * range; return (temp + minRange); } float NormalizeToRange(float normalizedValue) { - return (float)((normalizedValue / 2.0) + 0.5); + return static_cast(normalizedValue / 2.0 + 0.5); } /** @@ -274,7 +273,8 @@ void panInit(double period) { void panForTarget(Servo* panServo) { panForTarget(panServo, 0.0); } void panForTarget(Servo* panServo, double sinStart) { - float normalizedSinPosition = (float)SinPosition(nullptr, sinStart); + float normalizedSinPosition = + static_cast(SinPosition(nullptr, sinStart)); float newServoPosition = NormalizeToRange(normalizedSinPosition); panServo->Set(newServoPosition); // ShowActivity ("pan x: normalized %f newServoPosition = %f" , @@ -295,8 +295,8 @@ void panForTarget(Servo* panServo, double sinStart) { **/ int processFile(char* inputFile, char* outputString, int lineNumber) { FILE* infile; - const int stringSize = 80; // max size of one line in file - char inputStr[stringSize]; + const int kStringSize = 80; // max size of one line in file + char inputStr[kStringSize]; inputStr[0] = '\0'; int lineCount = 0; @@ -308,16 +308,16 @@ int processFile(char* inputFile, char* outputString, int lineNumber) { } while (!std::feof(infile)) { - if (std::fgets(inputStr, stringSize, infile) != nullptr) { + if (std::fgets(inputStr, kStringSize, infile) != nullptr) { // Skip empty lines if (emptyString(inputStr)) continue; // Skip comment lines if (inputStr[0] == '#' || inputStr[0] == '!') continue; lineCount++; - if (lineNumber == 0) + if (lineNumber == 0) { continue; - else { + } else { if (lineCount == lineNumber) break; } } diff --git a/wpilibc/athena/src/Vision/BinaryImage.cpp b/wpilibc/athena/src/Vision/BinaryImage.cpp index de6f651041..20a191ab73 100644 --- a/wpilibc/athena/src/Vision/BinaryImage.cpp +++ b/wpilibc/athena/src/Vision/BinaryImage.cpp @@ -157,7 +157,7 @@ bool BinaryImage::ParticleMeasurement(int particleNumber, double resultDouble; bool success = ParticleMeasurement(particleNumber, whatToMeasure, &resultDouble); - *result = (int)resultDouble; + *result = static_cast(resultDouble); return success; } @@ -184,7 +184,7 @@ bool BinaryImage::ParticleMeasurement(int particleNumber, // Normalizes to [-1,1] double BinaryImage::NormalizeFromRange(double position, int range) { - return (position * 2.0 / (double)range) - 1.0; + return position * 2.0 / static_cast(range) - 1.0; } /** diff --git a/wpilibc/athena/src/Vision/VisionAPI.cpp b/wpilibc/athena/src/Vision/VisionAPI.cpp index 9c1af736b2..9e8cbc8d8f 100644 --- a/wpilibc/athena/src/Vision/VisionAPI.cpp +++ b/wpilibc/athena/src/Vision/VisionAPI.cpp @@ -57,8 +57,7 @@ int frcDispose(void* object) { return imaqDispose(object); } * @return On success: 1. On failure: 0. To get extended error information, call * GetLastError(). */ -int frcDispose(const char* functionName, ...) /* Variable argument list */ -{ +int frcDispose(const char* functionName, ...) { va_list disposalPtrList; /* Input argument list */ void* disposalPtr; /* For iteration */ int success, returnValue = 1; @@ -281,7 +280,9 @@ ColorHistogramReport* frcColorHistogram(const Image* image, int numClasses, ColorHistogramReport* frcColorHistogram(const Image* image, int numClasses, ColorMode mode, Image* mask) { - return imaqColorHistogram2((Image*)image, numClasses, mode, nullptr, mask); + return imaqColorHistogram2( + const_cast(reinterpret_cast(image)), numClasses, + mode, nullptr, mask); } /** @@ -451,14 +452,14 @@ int frcParticleAnalysis(Image* image, int particleNumber, if (!success) { return success; } - par->center_mass_x = (int)returnDouble; // pixel + par->center_mass_x = static_cast(returnDouble); // pixel success = imaqMeasureParticle(image, particleNumber, 0, IMAQ_MT_CENTER_OF_MASS_Y, &returnDouble); if (!success) { return success; } - par->center_mass_y = (int)returnDouble; // pixel + par->center_mass_y = static_cast(returnDouble); // pixel /* particle size statistics */ success = imaqMeasureParticle(image, particleNumber, 0, IMAQ_MT_AREA, @@ -473,28 +474,28 @@ int frcParticleAnalysis(Image* image, int particleNumber, if (!success) { return success; } - par->boundingRect.top = (int)returnDouble; + par->boundingRect.top = static_cast(returnDouble); success = imaqMeasureParticle(image, particleNumber, 0, IMAQ_MT_BOUNDING_RECT_LEFT, &returnDouble); if (!success) { return success; } - par->boundingRect.left = (int)returnDouble; + par->boundingRect.left = static_cast(returnDouble); success = imaqMeasureParticle(image, particleNumber, 0, IMAQ_MT_BOUNDING_RECT_HEIGHT, &returnDouble); if (!success) { return success; } - par->boundingRect.height = (int)returnDouble; + par->boundingRect.height = static_cast(returnDouble); success = imaqMeasureParticle(image, particleNumber, 0, IMAQ_MT_BOUNDING_RECT_WIDTH, &returnDouble); if (!success) { return success; } - par->boundingRect.width = (int)returnDouble; + par->boundingRect.width = static_cast(returnDouble); /* particle quality statistics */ success = imaqMeasureParticle(image, particleNumber, 0, diff --git a/wpilibc/shared/include/Buttons/InternalButton.h b/wpilibc/shared/include/Buttons/InternalButton.h index fc804c9006..d35de60d39 100644 --- a/wpilibc/shared/include/Buttons/InternalButton.h +++ b/wpilibc/shared/include/Buttons/InternalButton.h @@ -12,7 +12,7 @@ class InternalButton : public Button { public: InternalButton() = default; - InternalButton(bool inverted); + explicit InternalButton(bool inverted); virtual ~InternalButton() = default; void SetInverted(bool inverted); diff --git a/wpilibc/shared/include/Buttons/Trigger.h b/wpilibc/shared/include/Buttons/Trigger.h index 729afa44b2..2dcf72f654 100644 --- a/wpilibc/shared/include/Buttons/Trigger.h +++ b/wpilibc/shared/include/Buttons/Trigger.h @@ -39,9 +39,9 @@ class Trigger : public Sendable { void CancelWhenActive(Command* command); void ToggleWhenActive(Command* command); - virtual void InitTable(std::shared_ptr table); - virtual std::shared_ptr GetTable() const; - virtual std::string GetSmartDashboardType() const; + void InitTable(std::shared_ptr subtable) override; + std::shared_ptr GetTable() const override; + std::string GetSmartDashboardType() const override; protected: std::shared_ptr m_table; diff --git a/wpilibc/shared/include/CircularBuffer.h b/wpilibc/shared/include/CircularBuffer.h index a8d76e2334..d865d96ab9 100644 --- a/wpilibc/shared/include/CircularBuffer.h +++ b/wpilibc/shared/include/CircularBuffer.h @@ -18,7 +18,7 @@ template class CircularBuffer { public: - CircularBuffer(size_t size); + explicit CircularBuffer(size_t size); void PushFront(T value); void PushBack(T value); diff --git a/wpilibc/shared/include/Commands/Command.h b/wpilibc/shared/include/Commands/Command.h index 2727829df8..1dc35db918 100644 --- a/wpilibc/shared/include/Commands/Command.h +++ b/wpilibc/shared/include/Commands/Command.h @@ -52,8 +52,8 @@ class Command : public ErrorBase, public NamedSendable, public ITableListener { public: Command(); - Command(const std::string& name); - Command(double timeout); + explicit Command(const std::string& name); + explicit Command(double timeout); Command(const std::string& name, double timeout); virtual ~Command(); double TimeSinceInitialized() const; @@ -167,12 +167,12 @@ class Command : public ErrorBase, public NamedSendable, public ITableListener { static int m_commandCounter; public: - virtual std::string GetName() const; - virtual void InitTable(std::shared_ptr table); - virtual std::shared_ptr GetTable() const; - virtual std::string GetSmartDashboardType() const; - virtual void ValueChanged(ITable* source, llvm::StringRef key, - std::shared_ptr value, bool isNew); + std::string GetName() const override; + void InitTable(std::shared_ptr subtable) override; + std::shared_ptr GetTable() const override; + std::string GetSmartDashboardType() const override; + void ValueChanged(ITable* source, llvm::StringRef key, + std::shared_ptr value, bool isNew) override; protected: std::shared_ptr m_table; diff --git a/wpilibc/shared/include/Commands/CommandGroup.h b/wpilibc/shared/include/Commands/CommandGroup.h index 1cb74fddcf..2b430c85eb 100644 --- a/wpilibc/shared/include/Commands/CommandGroup.h +++ b/wpilibc/shared/include/Commands/CommandGroup.h @@ -35,7 +35,7 @@ class CommandGroup : public Command { public: CommandGroup() = default; - CommandGroup(const std::string& name); + explicit CommandGroup(const std::string& name); virtual ~CommandGroup() = default; void AddSequential(Command* command); diff --git a/wpilibc/shared/include/Commands/PIDCommand.h b/wpilibc/shared/include/Commands/PIDCommand.h index 496513fa9f..de8165ecde 100644 --- a/wpilibc/shared/include/Commands/PIDCommand.h +++ b/wpilibc/shared/include/Commands/PIDCommand.h @@ -51,6 +51,6 @@ class PIDCommand : public Command, public PIDOutput, public PIDSource { std::shared_ptr m_controller; public: - virtual void InitTable(std::shared_ptr table); - virtual std::string GetSmartDashboardType() const; + void InitTable(std::shared_ptr subtable) override; + std::string GetSmartDashboardType() const override; }; diff --git a/wpilibc/shared/include/Commands/PIDSubsystem.h b/wpilibc/shared/include/Commands/PIDSubsystem.h index f5f13db903..4ed8688d6b 100644 --- a/wpilibc/shared/include/Commands/PIDSubsystem.h +++ b/wpilibc/shared/include/Commands/PIDSubsystem.h @@ -66,6 +66,6 @@ class PIDSubsystem : public Subsystem, public PIDOutput, public PIDSource { std::shared_ptr m_controller; public: - virtual void InitTable(std::shared_ptr table); - virtual std::string GetSmartDashboardType() const; + void InitTable(std::shared_ptr subtable) override; + std::string GetSmartDashboardType() const override; }; diff --git a/wpilibc/shared/include/Commands/PrintCommand.h b/wpilibc/shared/include/Commands/PrintCommand.h index e63dd2a9ad..fd5468f71e 100644 --- a/wpilibc/shared/include/Commands/PrintCommand.h +++ b/wpilibc/shared/include/Commands/PrintCommand.h @@ -12,7 +12,7 @@ class PrintCommand : public Command { public: - PrintCommand(const std::string& message); + explicit PrintCommand(const std::string& message); virtual ~PrintCommand() = default; protected: diff --git a/wpilibc/shared/include/Commands/StartCommand.h b/wpilibc/shared/include/Commands/StartCommand.h index 2daa147526..d54bd2beec 100644 --- a/wpilibc/shared/include/Commands/StartCommand.h +++ b/wpilibc/shared/include/Commands/StartCommand.h @@ -11,7 +11,7 @@ class StartCommand : public Command { public: - StartCommand(Command* commandToStart); + explicit StartCommand(Command* commandToStart); virtual ~StartCommand() = default; protected: diff --git a/wpilibc/shared/include/Commands/Subsystem.h b/wpilibc/shared/include/Commands/Subsystem.h index 64c85ba159..3baffef654 100644 --- a/wpilibc/shared/include/Commands/Subsystem.h +++ b/wpilibc/shared/include/Commands/Subsystem.h @@ -18,7 +18,7 @@ class Subsystem : public ErrorBase, public NamedSendable { friend class Scheduler; public: - Subsystem(const std::string& name); + explicit Subsystem(const std::string& name); virtual ~Subsystem() = default; void SetDefaultCommand(Command* command); @@ -37,10 +37,10 @@ class Subsystem : public ErrorBase, public NamedSendable { bool m_initializedDefaultCommand = false; public: - virtual std::string GetName() const; - virtual void InitTable(std::shared_ptr table); - virtual std::shared_ptr GetTable() const; - virtual std::string GetSmartDashboardType() const; + std::string GetName() const override; + void InitTable(std::shared_ptr subtable) override; + std::shared_ptr GetTable() const override; + std::string GetSmartDashboardType() const override; protected: std::shared_ptr m_table; diff --git a/wpilibc/shared/include/Commands/WaitCommand.h b/wpilibc/shared/include/Commands/WaitCommand.h index 2f10e96dd5..3845cf418b 100644 --- a/wpilibc/shared/include/Commands/WaitCommand.h +++ b/wpilibc/shared/include/Commands/WaitCommand.h @@ -11,7 +11,7 @@ class WaitCommand : public Command { public: - WaitCommand(double timeout); + explicit WaitCommand(double timeout); WaitCommand(const std::string& name, double timeout); virtual ~WaitCommand() = default; diff --git a/wpilibc/shared/include/Commands/WaitForChildren.h b/wpilibc/shared/include/Commands/WaitForChildren.h index b6fe1cc187..f7ab406bbb 100644 --- a/wpilibc/shared/include/Commands/WaitForChildren.h +++ b/wpilibc/shared/include/Commands/WaitForChildren.h @@ -11,7 +11,7 @@ class WaitForChildren : public Command { public: - WaitForChildren(double timeout); + explicit WaitForChildren(double timeout); WaitForChildren(const std::string& name, double timeout); virtual ~WaitForChildren() = default; diff --git a/wpilibc/shared/include/Commands/WaitUntilCommand.h b/wpilibc/shared/include/Commands/WaitUntilCommand.h index 1fda21fea0..5d941f552d 100644 --- a/wpilibc/shared/include/Commands/WaitUntilCommand.h +++ b/wpilibc/shared/include/Commands/WaitUntilCommand.h @@ -11,7 +11,7 @@ class WaitUntilCommand : public Command { public: - WaitUntilCommand(double time); + explicit WaitUntilCommand(double time); WaitUntilCommand(const std::string& name, double time); virtual ~WaitUntilCommand() = default; diff --git a/wpilibc/shared/include/Filters/Filter.h b/wpilibc/shared/include/Filters/Filter.h index 1ab193b00f..1f2a62039f 100644 --- a/wpilibc/shared/include/Filters/Filter.h +++ b/wpilibc/shared/include/Filters/Filter.h @@ -15,13 +15,13 @@ */ class Filter : public PIDSource { public: - Filter(std::shared_ptr source); + explicit Filter(std::shared_ptr source); virtual ~Filter() = default; // PIDSource interface - virtual void SetPIDSourceType(PIDSourceType pidSource) override; + void SetPIDSourceType(PIDSourceType pidSource) override; PIDSourceType GetPIDSourceType() const; - virtual double PIDGet() override = 0; + double PIDGet() override = 0; /** * Returns the current filter estimate without also inserting new data as diff --git a/wpilibc/shared/include/PIDController.h b/wpilibc/shared/include/PIDController.h index 01b1243759..bd54009d24 100644 --- a/wpilibc/shared/include/PIDController.h +++ b/wpilibc/shared/include/PIDController.h @@ -50,15 +50,15 @@ class PIDController : public LiveWindowSendable, virtual void SetContinuous(bool continuous = true); virtual void SetInputRange(float minimumInput, float maximumInput); virtual void SetOutputRange(float minimumOutput, float maximumOutput); - virtual void SetPID(double p, double i, double d) override; + void SetPID(double p, double i, double d) override; virtual void SetPID(double p, double i, double d, double f); - virtual double GetP() const override; - virtual double GetI() const override; - virtual double GetD() const override; + double GetP() const override; + double GetI() const override; + double GetD() const override; virtual double GetF() const; - virtual void SetSetpoint(float setpoint) override; - virtual double GetSetpoint() const override; + void SetSetpoint(float setpoint) override; + double GetSetpoint() const override; double GetDeltaSetpoint() const; virtual float GetError() const; @@ -73,13 +73,13 @@ class PIDController : public LiveWindowSendable, virtual void SetToleranceBuffer(unsigned buf = 1); virtual bool OnTarget() const; - virtual void Enable() override; - virtual void Disable() override; - virtual bool IsEnabled() const override; + void Enable() override; + void Disable() override; + bool IsEnabled() const override; - virtual void Reset() override; + void Reset() override; - virtual void InitTable(std::shared_ptr table) override; + void InitTable(std::shared_ptr subtable) override; protected: PIDSource* m_pidInput; @@ -141,12 +141,11 @@ class PIDController : public LiveWindowSendable, void Initialize(float p, float i, float d, float f, PIDSource* source, PIDOutput* output, float period = 0.05); - virtual std::shared_ptr GetTable() const override; - virtual std::string GetSmartDashboardType() const override; - virtual void ValueChanged(ITable* source, llvm::StringRef key, - std::shared_ptr value, - bool isNew) override; - virtual void UpdateTable() override; - virtual void StartLiveWindowMode() override; - virtual void StopLiveWindowMode() override; + std::shared_ptr GetTable() const override; + std::string GetSmartDashboardType() const override; + void ValueChanged(ITable* source, llvm::StringRef key, + std::shared_ptr value, bool isNew) override; + void UpdateTable() override; + void StartLiveWindowMode() override; + void StopLiveWindowMode() override; }; diff --git a/wpilibc/shared/include/SmartDashboard/SendableChooser.h b/wpilibc/shared/include/SmartDashboard/SendableChooser.h index 53aa4cf1e8..c2787ba318 100644 --- a/wpilibc/shared/include/SmartDashboard/SendableChooser.h +++ b/wpilibc/shared/include/SmartDashboard/SendableChooser.h @@ -34,9 +34,9 @@ class SendableChooser : public Sendable { void AddDefault(const std::string& name, void* object); void* GetSelected(); - virtual void InitTable(std::shared_ptr subtable); - virtual std::shared_ptr GetTable() const; - virtual std::string GetSmartDashboardType() const; + void InitTable(std::shared_ptr subtable) override; + std::shared_ptr GetTable() const override; + std::string GetSmartDashboardType() const override; private: std::string m_defaultChoice; diff --git a/wpilibc/shared/include/interfaces/Potentiometer.h b/wpilibc/shared/include/interfaces/Potentiometer.h index be48a55fa5..1848175121 100644 --- a/wpilibc/shared/include/interfaces/Potentiometer.h +++ b/wpilibc/shared/include/interfaces/Potentiometer.h @@ -23,5 +23,5 @@ class Potentiometer : public PIDSource { */ virtual double Get() const = 0; - virtual void SetPIDSourceType(PIDSourceType pidSource) override; + void SetPIDSourceType(PIDSourceType pidSource) override; }; diff --git a/wpilibc/shared/src/Buttons/Trigger.cpp b/wpilibc/shared/src/Buttons/Trigger.cpp index cd2bfd5911..54a409cea2 100644 --- a/wpilibc/shared/src/Buttons/Trigger.cpp +++ b/wpilibc/shared/src/Buttons/Trigger.cpp @@ -14,15 +14,13 @@ #include "Buttons/ToggleButtonScheduler.h" bool Trigger::Grab() { - if (Get()) + if (Get()) { return true; - else if (m_table != nullptr) { - // if (m_table->isConnected())//TODO is connected on button? + } else if (m_table != nullptr) { return m_table->GetBoolean("pressed", false); - /*else - return false;*/ - } else + } else { return false; + } } void Trigger::WhenActive(Command* command) { @@ -52,8 +50,8 @@ void Trigger::ToggleWhenActive(Command* command) { std::string Trigger::GetSmartDashboardType() const { return "Button"; } -void Trigger::InitTable(std::shared_ptr table) { - m_table = table; +void Trigger::InitTable(std::shared_ptr subtable) { + m_table = subtable; if (m_table != nullptr) { m_table->PutBoolean("pressed", Get()); } diff --git a/wpilibc/shared/src/Commands/Command.cpp b/wpilibc/shared/src/Commands/Command.cpp index 5298261806..2035505416 100644 --- a/wpilibc/shared/src/Commands/Command.cpp +++ b/wpilibc/shared/src/Commands/Command.cpp @@ -392,9 +392,9 @@ std::string Command::GetName() const { return m_name; } std::string Command::GetSmartDashboardType() const { return "Command"; } -void Command::InitTable(std::shared_ptr table) { +void Command::InitTable(std::shared_ptr subtable) { if (m_table != nullptr) m_table->RemoveTableListener(this); - m_table = table; + m_table = subtable; if (m_table != nullptr) { m_table->PutString(kName, GetName()); m_table->PutBoolean(kRunning, IsRunning()); diff --git a/wpilibc/shared/src/Commands/PIDCommand.cpp b/wpilibc/shared/src/Commands/PIDCommand.cpp index 816a86fd13..49fab7946c 100644 --- a/wpilibc/shared/src/Commands/PIDCommand.cpp +++ b/wpilibc/shared/src/Commands/PIDCommand.cpp @@ -66,7 +66,8 @@ double PIDCommand::GetSetpoint() const { return m_controller->GetSetpoint(); } double PIDCommand::GetPosition() { return ReturnPIDInput(); } std::string PIDCommand::GetSmartDashboardType() const { return "PIDCommand"; } -void PIDCommand::InitTable(std::shared_ptr table) { - m_controller->InitTable(table); - Command::InitTable(table); + +void PIDCommand::InitTable(std::shared_ptr subtable) { + m_controller->InitTable(subtable); + Command::InitTable(subtable); } diff --git a/wpilibc/shared/src/Commands/PIDSubsystem.cpp b/wpilibc/shared/src/Commands/PIDSubsystem.cpp index 39b54edd95..b153cf40c3 100644 --- a/wpilibc/shared/src/Commands/PIDSubsystem.cpp +++ b/wpilibc/shared/src/Commands/PIDSubsystem.cpp @@ -239,7 +239,8 @@ void PIDSubsystem::PIDWrite(float output) { UsePIDOutput(output); } double PIDSubsystem::PIDGet() { return ReturnPIDInput(); } std::string PIDSubsystem::GetSmartDashboardType() const { return "PIDCommand"; } -void PIDSubsystem::InitTable(std::shared_ptr table) { - m_controller->InitTable(table); - Subsystem::InitTable(table); + +void PIDSubsystem::InitTable(std::shared_ptr subtable) { + m_controller->InitTable(subtable); + Subsystem::InitTable(subtable); } diff --git a/wpilibc/shared/src/Commands/Scheduler.cpp b/wpilibc/shared/src/Commands/Scheduler.cpp index 300f07adce..8525a91dc5 100644 --- a/wpilibc/shared/src/Commands/Scheduler.cpp +++ b/wpilibc/shared/src/Commands/Scheduler.cpp @@ -225,7 +225,7 @@ void Scheduler::UpdateTable() { toCancel = new_toCancel->GetDoubleArray(); else toCancel.resize(0); - // m_table->RetrieveValue("Ids", *ids); + // m_table->RetrieveValue("Ids", *ids); // cancel commands that have had the cancel buttons pressed // on the SmartDashboad diff --git a/wpilibc/shared/src/Commands/Subsystem.cpp b/wpilibc/shared/src/Commands/Subsystem.cpp index fe63983732..a84f53a4b2 100644 --- a/wpilibc/shared/src/Commands/Subsystem.cpp +++ b/wpilibc/shared/src/Commands/Subsystem.cpp @@ -129,8 +129,8 @@ std::string Subsystem::GetName() const { return m_name; } std::string Subsystem::GetSmartDashboardType() const { return "Subsystem"; } -void Subsystem::InitTable(std::shared_ptr table) { - m_table = table; +void Subsystem::InitTable(std::shared_ptr subtable) { + m_table = subtable; if (m_table != nullptr) { if (m_defaultCommand != nullptr) { m_table->PutBoolean("hasDefault", true); diff --git a/wpilibc/sim/include/AnalogPotentiometer.h b/wpilibc/sim/include/AnalogPotentiometer.h index e0209d70ad..62acda5c24 100644 --- a/wpilibc/sim/include/AnalogPotentiometer.h +++ b/wpilibc/sim/include/AnalogPotentiometer.h @@ -36,7 +36,8 @@ class AnalogPotentiometer : public Potentiometer, public LiveWindowSendable { * @param offset The offset to add to the scaled value for controlling the * zero value */ - AnalogPotentiometer(int channel, double scale = 1.0, double offset = 0.0); + explicit AnalogPotentiometer(int channel, double scale = 1.0, + double offset = 0.0); AnalogPotentiometer(AnalogInput* input, double scale = 1.0, double offset = 0.0); @@ -58,27 +59,27 @@ class AnalogPotentiometer : public Potentiometer, public LiveWindowSendable { * * @return The current reading. */ - virtual double PIDGet() override; + double PIDGet() override; /* * Live Window code, only does anything if live window is activated. */ - virtual std::string GetSmartDashboardType() const override; - virtual void InitTable(std::shared_ptr subtable) override; - virtual void UpdateTable() override; - virtual std::shared_ptr GetTable() const override; + std::string GetSmartDashboardType() const override; + void InitTable(std::shared_ptr subtable) override; + void UpdateTable() override; + std::shared_ptr GetTable() const override; /** * AnalogPotentiometers don't have to do anything special when entering the * LiveWindow. */ - virtual void StartLiveWindowMode() override {} + void StartLiveWindowMode() override {} /** * AnalogPotentiometers don't have to do anything special when exiting the * LiveWindow. */ - virtual void StopLiveWindowMode() override {} + void StopLiveWindowMode() override {} private: double m_scale, m_offset; diff --git a/wpilibc/sim/include/Counter.h b/wpilibc/sim/include/Counter.h index 971f50ccf0..78f02bdad9 100644 --- a/wpilibc/sim/include/Counter.h +++ b/wpilibc/sim/include/Counter.h @@ -80,7 +80,7 @@ class Counter : public SensorBase, void UpdateTable() override; void StartLiveWindowMode() override; void StopLiveWindowMode() override; - virtual std::string GetSmartDashboardType() const override; + std::string GetSmartDashboardType() const override; void InitTable(std::shared_ptr subTable) override; std::shared_ptr GetTable() const override; diff --git a/wpilibc/sim/include/DriverStation.h b/wpilibc/sim/include/DriverStation.h index 00f71436a0..bb2a8b312d 100644 --- a/wpilibc/sim/include/DriverStation.h +++ b/wpilibc/sim/include/DriverStation.h @@ -48,7 +48,7 @@ class DriverStation : public SensorBase, public RobotStateInterface { float GetStickAxis(uint32_t stick, uint32_t axis); bool GetStickButton(uint32_t stick, uint32_t button); - short GetStickButtons(uint32_t stick); + int16_t GetStickButtons(uint32_t stick); float GetAnalogIn(uint32_t channel); bool GetDigitalIn(uint32_t channel); diff --git a/wpilibc/sim/include/Jaguar.h b/wpilibc/sim/include/Jaguar.h index b5dc1caf76..d412686d02 100644 --- a/wpilibc/sim/include/Jaguar.h +++ b/wpilibc/sim/include/Jaguar.h @@ -22,5 +22,5 @@ class Jaguar : public SafePWM, public SpeedController { virtual float Get() const; virtual void Disable(); - virtual void PIDWrite(float output) override; + void PIDWrite(float output) override; }; diff --git a/wpilibc/sim/include/Joystick.h b/wpilibc/sim/include/Joystick.h index 2421080e61..3a99a9b213 100644 --- a/wpilibc/sim/include/Joystick.h +++ b/wpilibc/sim/include/Joystick.h @@ -50,19 +50,19 @@ class Joystick : public GenericHID, public ErrorBase { uint32_t GetAxisChannel(AxisType axis); void SetAxisChannel(AxisType axis, uint32_t channel); - virtual float GetX(JoystickHand hand = kRightHand) const override; - virtual float GetY(JoystickHand hand = kRightHand) const override; - virtual float GetZ() const override; - virtual float GetTwist() const override; - virtual float GetThrottle() const override; + float GetX(JoystickHand hand = kRightHand) const override; + float GetY(JoystickHand hand = kRightHand) const override; + float GetZ() const override; + float GetTwist() const override; + float GetThrottle() const override; virtual float GetAxis(AxisType axis) const; float GetRawAxis(uint32_t axis) const override; - virtual bool GetTrigger(JoystickHand hand = kRightHand) const override; - virtual bool GetTop(JoystickHand hand = kRightHand) const override; - virtual bool GetBumper(JoystickHand hand = kRightHand) const override; - virtual bool GetRawButton(uint32_t button) const override; - virtual int GetPOV(uint32_t pov = 1) 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 GetButton(ButtonType button) const; static Joystick* GetStickForPort(uint32_t port); diff --git a/wpilibc/sim/include/MotorSafetyHelper.h b/wpilibc/sim/include/MotorSafetyHelper.h index 35ee64ce68..60fea90c33 100644 --- a/wpilibc/sim/include/MotorSafetyHelper.h +++ b/wpilibc/sim/include/MotorSafetyHelper.h @@ -16,7 +16,7 @@ class MotorSafety; class MotorSafetyHelper : public ErrorBase { public: - MotorSafetyHelper(MotorSafety* safeObject); + explicit MotorSafetyHelper(MotorSafety* safeObject); ~MotorSafetyHelper(); void Feed(); void SetExpiration(float expirationTime); diff --git a/wpilibc/sim/include/PWM.h b/wpilibc/sim/include/PWM.h index 61f70cebcb..8c475d9526 100644 --- a/wpilibc/sim/include/PWM.h +++ b/wpilibc/sim/include/PWM.h @@ -43,7 +43,7 @@ class PWM : public SensorBase, explicit PWM(uint32_t channel); virtual ~PWM(); - virtual void SetRaw(unsigned short value); + 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, diff --git a/wpilibc/sim/include/Relay.h b/wpilibc/sim/include/Relay.h index 46faffc52a..d67d176b1d 100644 --- a/wpilibc/sim/include/Relay.h +++ b/wpilibc/sim/include/Relay.h @@ -39,7 +39,7 @@ class Relay : public MotorSafety, enum Value { kOff, kOn, kForward, kReverse }; enum Direction { kBothDirections, kForwardOnly, kReverseOnly }; - Relay(uint32_t channel, Direction direction = kBothDirections); + explicit Relay(uint32_t channel, Direction direction = kBothDirections); virtual ~Relay(); void Set(Value value); diff --git a/wpilibc/sim/include/Talon.h b/wpilibc/sim/include/Talon.h index bcdaa211a3..5e6dc13e89 100644 --- a/wpilibc/sim/include/Talon.h +++ b/wpilibc/sim/include/Talon.h @@ -22,5 +22,5 @@ class Talon : public SafePWM, public SpeedController { virtual float Get() const; virtual void Disable(); - virtual void PIDWrite(float output) override; + void PIDWrite(float output) override; }; diff --git a/wpilibc/sim/include/Victor.h b/wpilibc/sim/include/Victor.h index 1b98816f7b..39b7fc4a9c 100644 --- a/wpilibc/sim/include/Victor.h +++ b/wpilibc/sim/include/Victor.h @@ -22,5 +22,5 @@ class Victor : public SafePWM, public SpeedController { virtual float Get() const; virtual void Disable(); - virtual void PIDWrite(float output) override; + void PIDWrite(float output) override; }; diff --git a/wpilibc/sim/include/simulation/SimContinuousOutput.h b/wpilibc/sim/include/simulation/SimContinuousOutput.h index 992ba5b11a..200c0119d7 100644 --- a/wpilibc/sim/include/simulation/SimContinuousOutput.h +++ b/wpilibc/sim/include/simulation/SimContinuousOutput.h @@ -24,7 +24,7 @@ class SimContinuousOutput { float speed; public: - SimContinuousOutput(std::string topic); + explicit SimContinuousOutput(std::string topic); /** * Set the output value. diff --git a/wpilibc/sim/include/simulation/SimDigitalInput.h b/wpilibc/sim/include/simulation/SimDigitalInput.h index 8a92e0f61d..c85da85f7e 100644 --- a/wpilibc/sim/include/simulation/SimDigitalInput.h +++ b/wpilibc/sim/include/simulation/SimDigitalInput.h @@ -14,7 +14,7 @@ using namespace gazebo; class SimDigitalInput { public: - SimDigitalInput(std::string topic); + explicit SimDigitalInput(std::string topic); /** * @return The value of the potentiometer. diff --git a/wpilibc/sim/include/simulation/SimEncoder.h b/wpilibc/sim/include/simulation/SimEncoder.h index 1e629e07c9..b81113b638 100644 --- a/wpilibc/sim/include/simulation/SimEncoder.h +++ b/wpilibc/sim/include/simulation/SimEncoder.h @@ -15,7 +15,7 @@ using namespace gazebo; class SimEncoder { public: - SimEncoder(std::string topic); + explicit SimEncoder(std::string topic); void Reset(); void Start(); diff --git a/wpilibc/sim/include/simulation/SimFloatInput.h b/wpilibc/sim/include/simulation/SimFloatInput.h index 1857ff218b..894ee7c8aa 100644 --- a/wpilibc/sim/include/simulation/SimFloatInput.h +++ b/wpilibc/sim/include/simulation/SimFloatInput.h @@ -14,7 +14,7 @@ using namespace gazebo; class SimFloatInput { public: - SimFloatInput(std::string topic); + explicit SimFloatInput(std::string topic); /** * @return The value of the potentiometer. diff --git a/wpilibc/sim/include/simulation/SimGyro.h b/wpilibc/sim/include/simulation/SimGyro.h index 8402170cd2..7884890c7d 100644 --- a/wpilibc/sim/include/simulation/SimGyro.h +++ b/wpilibc/sim/include/simulation/SimGyro.h @@ -14,7 +14,7 @@ using namespace gazebo; class SimGyro { public: - SimGyro(std::string topic); + explicit SimGyro(std::string topic); void Reset(); double GetAngle(); diff --git a/wpilibc/sim/src/AnalogGyro.cpp b/wpilibc/sim/src/AnalogGyro.cpp index 686d0eae9d..6677f48ad8 100644 --- a/wpilibc/sim/src/AnalogGyro.cpp +++ b/wpilibc/sim/src/AnalogGyro.cpp @@ -7,7 +7,7 @@ #include "AnalogGyro.h" -#include +#include #include "LiveWindow/LiveWindow.h" #include "Timer.h" @@ -32,9 +32,9 @@ const float AnalogGyro::kDefaultVoltsPerDegreePerSecond = 0.007; void AnalogGyro::InitAnalogGyro(int channel) { SetPIDSourceType(PIDSourceType::kDisplacement); - char buffer[50]; - int n = std::sprintf(buffer, "analog/%d", channel); - impl = new SimGyro(buffer); + std::stringstream ss; + ss << "analog/" << channel; + impl = new SimGyro(ss.str()); LiveWindow::GetInstance()->AddSensor("AnalogGyro", channel, this); } diff --git a/wpilibc/sim/src/AnalogInput.cpp b/wpilibc/sim/src/AnalogInput.cpp index 5e3dc51749..08d432fcaa 100644 --- a/wpilibc/sim/src/AnalogInput.cpp +++ b/wpilibc/sim/src/AnalogInput.cpp @@ -7,7 +7,7 @@ #include "AnalogInput.h" -#include +#include #include "LiveWindow/LiveWindow.h" #include "WPIErrors.h" @@ -17,11 +17,10 @@ * * @param channel The channel number to represent. */ -AnalogInput::AnalogInput(uint32_t channel) { - m_channel = channel; - char buffer[50]; - int n = std::sprintf(buffer, "analog/%d", channel); - m_impl = new SimFloatInput(buffer); +AnalogInput::AnalogInput(uint32_t channel) : m_channel(channel) { + std::stringstream ss; + ss << "analog/" << channel; + m_impl = new SimFloatInput(ss.str()); LiveWindow::GetInstance()->AddSensor("AnalogInput", channel, this); } diff --git a/wpilibc/sim/src/DigitalInput.cpp b/wpilibc/sim/src/DigitalInput.cpp index 344f96b8fb..5e333d31e2 100644 --- a/wpilibc/sim/src/DigitalInput.cpp +++ b/wpilibc/sim/src/DigitalInput.cpp @@ -7,7 +7,7 @@ #include "DigitalInput.h" -#include +#include #include "WPIErrors.h" @@ -17,11 +17,10 @@ * * @param channel The digital channel (1..14). */ -DigitalInput::DigitalInput(uint32_t channel) { - char buf[64]; - m_channel = channel; - int n = std::sprintf(buf, "dio/%d", channel); - m_impl = new SimDigitalInput(buf); +DigitalInput::DigitalInput(uint32_t channel) : m_channel(channel) { + std::stringstream ss; + ss << "dio/" << channel; + m_impl = new SimDigitalInput(ss.str()); } /** diff --git a/wpilibc/sim/src/DoubleSolenoid.cpp b/wpilibc/sim/src/DoubleSolenoid.cpp index ed1f6e998d..4ca0a0d3e7 100644 --- a/wpilibc/sim/src/DoubleSolenoid.cpp +++ b/wpilibc/sim/src/DoubleSolenoid.cpp @@ -35,10 +35,10 @@ DoubleSolenoid::DoubleSolenoid(uint8_t moduleNumber, uint32_t forwardChannel, forwardChannel = channel; m_reversed = true; } - char buffer[50]; - int n = std::sprintf(buffer, "pneumatic/%d/%d/%d/%d", moduleNumber, - forwardChannel, moduleNumber, reverseChannel); - m_impl = new SimContinuousOutput(buffer); + std::stringstream ss; + ss << "pneumatic/" << moduleNumber << "/" << forwardChannel << "/" + << moduleNumber << "/" << reverseChannel; + m_impl = new SimContinuousOutput(ss.str()); LiveWindow::GetInstance()->AddActuator("DoubleSolenoid", moduleNumber, forwardChannel, this); diff --git a/wpilibc/sim/src/DriverStation.cpp b/wpilibc/sim/src/DriverStation.cpp index cd0a57d4ef..15d3fbe349 100644 --- a/wpilibc/sim/src/DriverStation.cpp +++ b/wpilibc/sim/src/DriverStation.cpp @@ -128,13 +128,13 @@ bool DriverStation::GetStickButton(uint32_t stick, uint32_t button) { * @param stick The joystick to read. * @return The state of the buttons on the joystick. */ -short DriverStation::GetStickButtons(uint32_t stick) { +int16_t DriverStation::GetStickButtons(uint32_t stick) { if (stick < 0 || stick >= 6) { wpi_setWPIErrorWithContext(ParameterOutOfRange, "stick must be between 0 and 5"); return false; } - short btns = 0, btnid; + int16_t btns = 0, btnid; std::unique_lock lock(m_joystickMutex); msgs::FRCJoystickPtr joy = joysticks[stick]; @@ -147,7 +147,7 @@ short DriverStation::GetStickButtons(uint32_t stick) { } // 5V divided by 10 bits -#define kDSAnalogInScaling ((float)(5.0 / 1023.0)) +#define kDSAnalogInScaling (static_cast(5.0 / 1023.0)) /** * Get an analog voltage from the Driver Station. diff --git a/wpilibc/sim/src/Encoder.cpp b/wpilibc/sim/src/Encoder.cpp index ed28752080..0c6792cf53 100644 --- a/wpilibc/sim/src/Encoder.cpp +++ b/wpilibc/sim/src/Encoder.cpp @@ -7,7 +7,7 @@ #include "Encoder.h" -#include +#include #include "LiveWindow/LiveWindow.h" #include "Resource.h" @@ -51,9 +51,9 @@ void Encoder::InitEncoder(int32_t channelA, int32_t channelB, } else { m_reverseDirection = reverseDirection; } - char buffer[50]; - int n = std::sprintf(buffer, "dio/%d/%d", channelA, channelB); - impl = new SimEncoder(buffer); + std::stringstream ss; + ss << "dio/" << channelA << "/" << channelB; + impl = new SimEncoder(ss.str()); impl->Start(); } diff --git a/wpilibc/sim/src/Notifier.cpp b/wpilibc/sim/src/Notifier.cpp index 7dd5b833f6..49ea408b69 100644 --- a/wpilibc/sim/src/Notifier.cpp +++ b/wpilibc/sim/src/Notifier.cpp @@ -82,8 +82,9 @@ void Notifier::UpdateAlarm() {} */ void Notifier::ProcessQueue(uint32_t mask, void* params) { Notifier* current; - while (true) // keep processing past events until no more - { + + // keep processing events until no more + while (true) { { std::lock_guard sync(queueMutex); double currentTime = GetClock(); diff --git a/wpilibc/sim/src/PWM.cpp b/wpilibc/sim/src/PWM.cpp index 030a9d0511..803593d4e1 100644 --- a/wpilibc/sim/src/PWM.cpp +++ b/wpilibc/sim/src/PWM.cpp @@ -7,6 +7,8 @@ #include "PWM.h" +#include + #include "Utility.h" #include "WPIErrors.h" @@ -26,16 +28,16 @@ const int32_t PWM::kPwmDisabled = 0; * port */ PWM::PWM(uint32_t channel) { - char buf[64]; + std::stringstream ss; if (!CheckPWMChannel(channel)) { - std::snprintf(buf, 64, "PWM Channel %d", channel); - wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf); + ss << "PWM Channel " << channel; + wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, ss.str()); return; } - std::sprintf(buf, "pwm/%d", channel); - impl = new SimContinuousOutput(buf); + ss << "pwm/" << channel; + impl = new SimContinuousOutput(ss.str()); m_channel = channel; m_eliminateDeadband = false; @@ -189,7 +191,7 @@ float PWM::GetSpeed() const { * * @param value Raw PWM value. */ -void PWM::SetRaw(unsigned short value) { +void PWM::SetRaw(uint16_t value) { wpi_assert(value == kPwmDisabled); impl->Set(0); } diff --git a/wpilibc/sim/src/Relay.cpp b/wpilibc/sim/src/Relay.cpp index 85017b3070..5bb7dbef6b 100644 --- a/wpilibc/sim/src/Relay.cpp +++ b/wpilibc/sim/src/Relay.cpp @@ -7,6 +7,8 @@ #include "Relay.h" +#include + #include "LiveWindow/LiveWindow.h" #include "MotorSafetyHelper.h" #include "WPIErrors.h" @@ -22,21 +24,21 @@ */ Relay::Relay(uint32_t channel, Relay::Direction direction) : m_channel(channel), m_direction(direction) { - char buf[64]; + std::stringstream ss; if (!SensorBase::CheckRelayChannel(m_channel)) { - std::snprintf(buf, 64, "Relay Channel %d", m_channel); - wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf); + ss << "Relay Channel " << m_channel; + wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, ss.str()); return; } m_safetyHelper = std::make_unique(this); m_safetyHelper->SetSafetyEnabled(false); - std::sprintf(buf, "relay/%d", m_channel); - impl = new SimContinuousOutput(buf); // TODO: Allow two different relays - // (targetting the different halves of a - // relay) to be combined to control one - // motor. + ss << "relay/" << m_channel; + impl = new SimContinuousOutput(ss.str()); // TODO: Allow two different relays + // (targetting the different halves + // of a relay) to be combined to + // control one motor. LiveWindow::GetInstance()->AddActuator("Relay", 1, m_channel, this); go_pos = go_neg = false; } diff --git a/wpilibc/sim/src/Solenoid.cpp b/wpilibc/sim/src/Solenoid.cpp index e789eed2d9..f2d658f48b 100644 --- a/wpilibc/sim/src/Solenoid.cpp +++ b/wpilibc/sim/src/Solenoid.cpp @@ -7,7 +7,7 @@ #include "Solenoid.h" -#include +#include #include "LiveWindow/LiveWindow.h" #include "WPIErrors.h" @@ -27,9 +27,9 @@ Solenoid::Solenoid(uint32_t channel) : Solenoid(1, channel) {} * @param channel The channel on the solenoid module to control (1..8). */ Solenoid::Solenoid(uint8_t moduleNumber, uint32_t channel) { - char buffer[50]; - int n = std::sprintf(buffer, "pneumatic/%d/%d", moduleNumber, channel); - m_impl = new SimContinuousOutput(buffer); + std::stringstream ss; + ss << "pneumatic/" << moduleNumber << "/" << channel; + m_impl = new SimContinuousOutput(ss.str()); LiveWindow::GetInstance()->AddActuator("Solenoid", moduleNumber, channel, this); diff --git a/wpilibc/sim/src/Timer.cpp b/wpilibc/sim/src/Timer.cpp index 46d36cad2d..8a719efa25 100644 --- a/wpilibc/sim/src/Timer.cpp +++ b/wpilibc/sim/src/Timer.cpp @@ -24,7 +24,7 @@ void time_callback(const msgs::ConstFloat64Ptr& msg) { time_wait.notify_all(); } } -} +} // namespace wpilib /** * Pause the task for a specified time. diff --git a/wpilibc/sim/src/Utility.cpp b/wpilibc/sim/src/Utility.cpp index d296784777..db1dc106b1 100644 --- a/wpilibc/sim/src/Utility.cpp +++ b/wpilibc/sim/src/Utility.cpp @@ -40,8 +40,8 @@ void wpi_suspendOnAssertEnabled(bool enabled) { static void wpi_handleTracing() { // if (stackTraceEnabled) // { - // std::printf("\n---------------------------\n"); - // printCurrentStackTrace(); + // std::printf("\n---------------------------\n"); + // printCurrentStackTrace(); // } std::printf("\n"); } diff --git a/wpilibcIntegrationTests/src/AnalogLoopTest.cpp b/wpilibcIntegrationTests/src/AnalogLoopTest.cpp index 7a7ed2b30a..855c6a5ea6 100644 --- a/wpilibcIntegrationTests/src/AnalogLoopTest.cpp +++ b/wpilibcIntegrationTests/src/AnalogLoopTest.cpp @@ -24,12 +24,12 @@ class AnalogLoopTest : public testing::Test { AnalogInput* m_input; AnalogOutput* m_output; - virtual void SetUp() override { + void SetUp() override { m_input = new AnalogInput(TestBench::kFakeAnalogOutputChannel); m_output = new AnalogOutput(TestBench::kAnalogOutputChannel); } - virtual void TearDown() override { + void TearDown() override { delete m_input; delete m_output; } @@ -104,7 +104,7 @@ TEST_F(AnalogLoopTest, AnalogTriggerCounterWorks) { } static void InterruptHandler(uint32_t interruptAssertedMask, void* param) { - *(int*)param = 12345; + *reinterpret_cast(param) = 12345; } TEST_F(AnalogLoopTest, AsynchronusInterruptWorks) { diff --git a/wpilibcIntegrationTests/src/AnalogPotentiometerTest.cpp b/wpilibcIntegrationTests/src/AnalogPotentiometerTest.cpp index 2b204ff963..9ab9555533 100644 --- a/wpilibcIntegrationTests/src/AnalogPotentiometerTest.cpp +++ b/wpilibcIntegrationTests/src/AnalogPotentiometerTest.cpp @@ -22,13 +22,13 @@ class AnalogPotentiometerTest : public testing::Test { AnalogOutput* m_fakePot; AnalogPotentiometer* m_pot; - virtual void SetUp() override { + void SetUp() override { m_fakePot = new AnalogOutput(TestBench::kAnalogOutputChannel); m_pot = new AnalogPotentiometer(TestBench::kFakeAnalogOutputChannel, kScale); } - virtual void TearDown() override { + void TearDown() override { delete m_fakePot; delete m_pot; } diff --git a/wpilibcIntegrationTests/src/CANJaguarTest.cpp b/wpilibcIntegrationTests/src/CANJaguarTest.cpp index 5099adec79..f90ec97003 100644 --- a/wpilibcIntegrationTests/src/CANJaguarTest.cpp +++ b/wpilibcIntegrationTests/src/CANJaguarTest.cpp @@ -46,7 +46,7 @@ class CANJaguarTest : public testing::Test { AnalogOutput* m_fakePotentiometer; Relay* m_spike; - virtual void SetUp() override { + void SetUp() override { m_spike = new Relay(TestBench::kCANJaguarRelayChannel, Relay::kForwardOnly); m_spike->Set(Relay::kOn); Wait(kSpikeTime); @@ -66,7 +66,7 @@ class CANJaguarTest : public testing::Test { Wait(kEncoderSettlingTime); } - virtual void TearDown() override { + void TearDown() override { delete m_jaguar; delete m_fakeForwardLimit; delete m_fakeReverseLimit; diff --git a/wpilibcIntegrationTests/src/ConditionVariableTest.cpp b/wpilibcIntegrationTests/src/ConditionVariableTest.cpp index a6979b853e..ca8bb45ee1 100644 --- a/wpilibcIntegrationTests/src/ConditionVariableTest.cpp +++ b/wpilibcIntegrationTests/src/ConditionVariableTest.cpp @@ -41,7 +41,7 @@ class ConditionVariableTest : public ::testing::Test { // Information for when running with predicates. std::atomic m_pred_var{false}; - void ShortSleep(unsigned long time = 10) { + void ShortSleep(uint32_t time = 10) { std::this_thread::sleep_for(std::chrono::milliseconds(time)); } diff --git a/wpilibcIntegrationTests/src/CounterTest.cpp b/wpilibcIntegrationTests/src/CounterTest.cpp index d6e89eff73..5a43accb73 100644 --- a/wpilibcIntegrationTests/src/CounterTest.cpp +++ b/wpilibcIntegrationTests/src/CounterTest.cpp @@ -28,7 +28,7 @@ class CounterTest : public testing::Test { Victor* m_victor; Jaguar* m_jaguar; - virtual void SetUp() override { + void SetUp() override { m_talonCounter = new Counter(TestBench::kTalonEncoderChannelA); m_victorCounter = new Counter(TestBench::kVictorEncoderChannelA); m_jaguarCounter = new Counter(TestBench::kJaguarEncoderChannelA); @@ -37,7 +37,7 @@ class CounterTest : public testing::Test { m_jaguar = new Jaguar(TestBench::kJaguarChannel); } - virtual void TearDown() override { + void TearDown() override { delete m_talonCounter; delete m_victorCounter; delete m_jaguarCounter; diff --git a/wpilibcIntegrationTests/src/DIOLoopTest.cpp b/wpilibcIntegrationTests/src/DIOLoopTest.cpp index e7d64d4821..69dcb71870 100644 --- a/wpilibcIntegrationTests/src/DIOLoopTest.cpp +++ b/wpilibcIntegrationTests/src/DIOLoopTest.cpp @@ -31,12 +31,12 @@ class DIOLoopTest : public testing::Test { DigitalInput* m_input; DigitalOutput* m_output; - virtual void SetUp() override { + void SetUp() override { m_input = new DigitalInput(TestBench::kLoop1InputChannel); m_output = new DigitalOutput(TestBench::kLoop1OutputChannel); } - virtual void TearDown() override { + void TearDown() override { delete m_input; delete m_output; } @@ -140,7 +140,7 @@ TEST_F(DIOLoopTest, FakeCounter) { } static void InterruptHandler(uint32_t interruptAssertedMask, void* param) { - *(int*)param = 12345; + *reinterpret_cast(param) = 12345; } TEST_F(DIOLoopTest, AsynchronousInterruptWorks) { diff --git a/wpilibcIntegrationTests/src/FakeEncoderTest.cpp b/wpilibcIntegrationTests/src/FakeEncoderTest.cpp index ccb2c042e9..10db9ac132 100644 --- a/wpilibcIntegrationTests/src/FakeEncoderTest.cpp +++ b/wpilibcIntegrationTests/src/FakeEncoderTest.cpp @@ -27,7 +27,7 @@ class FakeEncoderTest : public testing::Test { AnalogTrigger* m_indexAnalogTrigger; std::shared_ptr m_indexAnalogTriggerOutput; - virtual void SetUp() override { + void SetUp() override { m_outputA = new DigitalOutput(TestBench::kLoop2OutputChannel); m_outputB = new DigitalOutput(TestBench::kLoop1OutputChannel); m_indexOutput = new AnalogOutput(TestBench::kAnalogOutputChannel); @@ -42,7 +42,7 @@ class FakeEncoderTest : public testing::Test { m_indexAnalogTrigger->CreateOutput(AnalogTriggerType::kState); } - virtual void TearDown() override { + void TearDown() override { delete m_outputA; delete m_outputB; delete m_indexOutput; diff --git a/wpilibcIntegrationTests/src/FilterOutputTest.cpp b/wpilibcIntegrationTests/src/FilterOutputTest.cpp index 9e4122adea..9f4663b5b9 100644 --- a/wpilibcIntegrationTests/src/FilterOutputTest.cpp +++ b/wpilibcIntegrationTests/src/FilterOutputTest.cpp @@ -38,7 +38,7 @@ std::ostream& operator<<(std::ostream& os, const FilterOutputTestType& type) { class DataWrapper : public PIDSource { public: - DataWrapper(double (*dataFunc)(double)) { m_dataFunc = dataFunc; } + explicit DataWrapper(double (*dataFunc)(double)) { m_dataFunc = dataFunc; } virtual void SetPIDSourceType(PIDSourceType pidSource) {} diff --git a/wpilibcIntegrationTests/src/MotorEncoderTest.cpp b/wpilibcIntegrationTests/src/MotorEncoderTest.cpp index 3dac1d2784..49ce3dc001 100644 --- a/wpilibcIntegrationTests/src/MotorEncoderTest.cpp +++ b/wpilibcIntegrationTests/src/MotorEncoderTest.cpp @@ -44,7 +44,7 @@ class MotorEncoderTest : public testing::TestWithParam { SpeedController* m_speedController; Encoder* m_encoder; - virtual void SetUp() override { + void SetUp() override { switch (GetParam()) { case TEST_VICTOR: m_speedController = new Victor(TestBench::kVictorChannel); @@ -66,7 +66,7 @@ class MotorEncoderTest : public testing::TestWithParam { } } - virtual void TearDown() override { + void TearDown() override { delete m_speedController; delete m_encoder; } diff --git a/wpilibcIntegrationTests/src/MotorInvertingTest.cpp b/wpilibcIntegrationTests/src/MotorInvertingTest.cpp index 2d7a041519..d81e884a9a 100644 --- a/wpilibcIntegrationTests/src/MotorInvertingTest.cpp +++ b/wpilibcIntegrationTests/src/MotorInvertingTest.cpp @@ -37,7 +37,7 @@ class MotorInvertingTest protected: SpeedController* m_speedController; Encoder* m_encoder; - virtual void SetUp() override { + void SetUp() override { switch (GetParam()) { case TEST_VICTOR: m_speedController = new Victor(TestBench::kVictorChannel); @@ -58,7 +58,7 @@ class MotorInvertingTest break; } } - virtual void TearDown() override { + void TearDown() override { delete m_speedController; delete m_encoder; } diff --git a/wpilibcIntegrationTests/src/MutexTest.cpp b/wpilibcIntegrationTests/src/MutexTest.cpp index d637030a1e..901d1b1e35 100644 --- a/wpilibcIntegrationTests/src/MutexTest.cpp +++ b/wpilibcIntegrationTests/src/MutexTest.cpp @@ -53,15 +53,15 @@ void SetProcessorAffinity(int core_id) { CPU_SET(core_id, &cpuset); pthread_t current_thread = pthread_self(); - ASSERT_TRUE( - pthread_setaffinity_np(current_thread, sizeof(cpu_set_t), &cpuset) == 0); + ASSERT_EQ(pthread_setaffinity_np(current_thread, sizeof(cpu_set_t), &cpuset), + 0); } void SetThreadRealtimePriorityOrDie(int priority) { struct sched_param param; // Set realtime priority for this thread param.sched_priority = priority + sched_get_priority_min(SCHED_RR); - ASSERT_TRUE(pthread_setschedparam(pthread_self(), SCHED_RR, ¶m) == 0) + ASSERT_EQ(pthread_setschedparam(pthread_self(), SCHED_RR, ¶m), 0) << ": Failed to set scheduler priority."; } @@ -69,7 +69,7 @@ void SetThreadRealtimePriorityOrDie(int priority) { template class LowPriorityThread { public: - LowPriorityThread(MutexType* mutex) + explicit LowPriorityThread(MutexType* mutex) : m_mutex(mutex), m_hold_mutex(1), m_success(0) {} void operator()() { @@ -137,7 +137,7 @@ class BusyWaitingThread { template class HighPriorityThread { public: - HighPriorityThread(MutexType* mutex) : m_mutex(mutex), m_success(0) {} + explicit HighPriorityThread(MutexType* mutex) : m_mutex(mutex) {} void operator()() { SetProcessorAffinity(0); @@ -153,7 +153,7 @@ class HighPriorityThread { private: Notification m_started; MutexType* m_mutex; - std::atomic m_success; + std::atomic m_success{0}; }; // Class to test a MutexType to see if it solves the priority inheritance diff --git a/wpilibcIntegrationTests/src/PCMTest.cpp b/wpilibcIntegrationTests/src/PCMTest.cpp index 7a1a3279c6..3df651b684 100644 --- a/wpilibcIntegrationTests/src/PCMTest.cpp +++ b/wpilibcIntegrationTests/src/PCMTest.cpp @@ -37,7 +37,7 @@ class PCMTest : public testing::Test { DoubleSolenoid* m_doubleSolenoid; DigitalInput *m_fakeSolenoid1, *m_fakeSolenoid2; - virtual void SetUp() override { + void SetUp() override { m_compressor = new Compressor(); m_fakePressureSwitch = @@ -47,7 +47,7 @@ class PCMTest : public testing::Test { m_fakeSolenoid2 = new DigitalInput(TestBench::kFakeSolenoid2Channel); } - virtual void TearDown() override { + void TearDown() override { delete m_compressor; delete m_fakePressureSwitch; delete m_fakeCompressor; diff --git a/wpilibcIntegrationTests/src/PIDToleranceTest.cpp b/wpilibcIntegrationTests/src/PIDToleranceTest.cpp index 7e5b33d382..2dac7f69a7 100644 --- a/wpilibcIntegrationTests/src/PIDToleranceTest.cpp +++ b/wpilibcIntegrationTests/src/PIDToleranceTest.cpp @@ -23,10 +23,7 @@ class PIDToleranceTest : public testing::Test { double val = 0; void SetPIDSourceType(PIDSourceType pidSource) {} PIDSourceType GetPIDSourceType() { return PIDSourceType::kDisplacement; } - double PIDGet() { - ; - return val; - } + double PIDGet() { return val; } }; class fakeOutput : public PIDOutput { void PIDWrite(float output) {} @@ -34,16 +31,16 @@ class PIDToleranceTest : public testing::Test { fakeInput inp; fakeOutput out; PIDController* pid; - virtual void SetUp() override { + void SetUp() override { pid = new PIDController(0.5, 0.0, 0.0, &inp, &out); pid->SetInputRange(-range / 2, range / 2); } - virtual void TearDown() override { delete pid; } - virtual void reset() { inp.val = 0; } + void TearDown() override { delete pid; } + void Reset() { inp.val = 0; } }; TEST_F(PIDToleranceTest, Absolute) { - reset(); + Reset(); pid->SetAbsoluteTolerance(tolerance); pid->SetSetpoint(setpoint); pid->Enable(); @@ -63,7 +60,7 @@ TEST_F(PIDToleranceTest, Absolute) { } TEST_F(PIDToleranceTest, Percent) { - reset(); + Reset(); pid->SetPercentTolerance(tolerance); pid->SetSetpoint(setpoint); pid->Enable(); diff --git a/wpilibcIntegrationTests/src/PowerDistributionPanelTest.cpp b/wpilibcIntegrationTests/src/PowerDistributionPanelTest.cpp index 4e43e47d7a..cc4b30e88c 100644 --- a/wpilibcIntegrationTests/src/PowerDistributionPanelTest.cpp +++ b/wpilibcIntegrationTests/src/PowerDistributionPanelTest.cpp @@ -24,14 +24,14 @@ class PowerDistributionPanelTest : public testing::Test { Victor* m_victor; Jaguar* m_jaguar; - virtual void SetUp() override { + void SetUp() override { m_pdp = new PowerDistributionPanel(); m_talon = new Talon(TestBench::kTalonChannel); m_victor = new Victor(TestBench::kVictorChannel); m_jaguar = new Jaguar(TestBench::kJaguarChannel); } - virtual void TearDown() override { + void TearDown() override { delete m_pdp; delete m_talon; delete m_victor; diff --git a/wpilibcIntegrationTests/src/RelayTest.cpp b/wpilibcIntegrationTests/src/RelayTest.cpp index 2779f78ddc..c0ef8c4bf4 100644 --- a/wpilibcIntegrationTests/src/RelayTest.cpp +++ b/wpilibcIntegrationTests/src/RelayTest.cpp @@ -21,19 +21,19 @@ class RelayTest : public testing::Test { DigitalInput* m_forward; DigitalInput* m_reverse; - virtual void SetUp() override { + void SetUp() override { m_relay = new Relay(TestBench::kRelayChannel); m_forward = new DigitalInput(TestBench::kFakeRelayForward); m_reverse = new DigitalInput(TestBench::kFakeRelayReverse); } - virtual void TearDown() override { + void TearDown() override { delete m_relay; delete m_forward; delete m_reverse; } - virtual void Reset() { m_relay->Set(Relay::kOff); } + void Reset() { m_relay->Set(Relay::kOff); } }; /** * Test the relay by setting it forward, reverse, off, and on. diff --git a/wpilibcIntegrationTests/src/TestEnvironment.cpp b/wpilibcIntegrationTests/src/TestEnvironment.cpp index be51dee8fa..a843425cbc 100644 --- a/wpilibcIntegrationTests/src/TestEnvironment.cpp +++ b/wpilibcIntegrationTests/src/TestEnvironment.cpp @@ -15,7 +15,7 @@ class TestEnvironment : public testing::Environment { bool m_alreadySetUp = false; public: - virtual void SetUp() override { + void SetUp() override { /* Only set up once. This allows gtest_repeat to be used to automatically repeat tests. */ if (m_alreadySetUp) return; @@ -40,7 +40,7 @@ class TestEnvironment : public testing::Environment { } } - virtual void TearDown() override {} + void TearDown() override {} }; testing::Environment* const environment = diff --git a/wpilibcIntegrationTests/src/TiltPanCameraTest.cpp b/wpilibcIntegrationTests/src/TiltPanCameraTest.cpp index 61430d2ec7..4a6bc650b8 100644 --- a/wpilibcIntegrationTests/src/TiltPanCameraTest.cpp +++ b/wpilibcIntegrationTests/src/TiltPanCameraTest.cpp @@ -42,7 +42,7 @@ class TiltPanCameraTest : public testing::Test { static void TearDownTestCase() { delete m_gyro; } - virtual void SetUp() override { + void SetUp() override { m_tilt = new Servo(TestBench::kCameraTiltChannel); m_pan = new Servo(TestBench::kCameraPanChannel); m_spiAccel = new ADXL345_SPI(SPI::kOnboardCS0); @@ -59,7 +59,7 @@ class TiltPanCameraTest : public testing::Test { void GyroAngle(); void GyroCalibratedParameters(); - virtual void TearDown() override { + void TearDown() override { delete m_tilt; delete m_pan; delete m_spiAccel; diff --git a/wpilibcIntegrationTests/src/TimerTest.cpp b/wpilibcIntegrationTests/src/TimerTest.cpp index 670387e093..565153c2d2 100644 --- a/wpilibcIntegrationTests/src/TimerTest.cpp +++ b/wpilibcIntegrationTests/src/TimerTest.cpp @@ -17,9 +17,9 @@ class TimerTest : public testing::Test { protected: Timer* m_timer; - virtual void SetUp() override { m_timer = new Timer; } + void SetUp() override { m_timer = new Timer; } - virtual void TearDown() override { delete m_timer; } + void TearDown() override { delete m_timer; } void Reset() { m_timer->Reset(); } }; diff --git a/wpilibcIntegrationTests/src/command/CommandTest.cpp b/wpilibcIntegrationTests/src/command/CommandTest.cpp index f7f905c204..be1b3a66a0 100644 --- a/wpilibcIntegrationTests/src/command/CommandTest.cpp +++ b/wpilibcIntegrationTests/src/command/CommandTest.cpp @@ -17,7 +17,7 @@ class CommandTest : public testing::Test { protected: - virtual void SetUp() override { + void SetUp() override { RobotState::SetImplementation(DriverStation::GetInstance()); Scheduler::GetInstance()->SetEnabled(true); } @@ -48,9 +48,9 @@ class ASubsystem : public Subsystem { Command* m_command = nullptr; public: - ASubsystem(const std::string& name) : Subsystem(name) {} + explicit ASubsystem(const std::string& name) : Subsystem(name) {} - virtual void InitDefaultCommand() override { + void InitDefaultCommand() override { if (m_command != nullptr) { SetDefaultCommand(m_command); } diff --git a/wpilibj/src/athena/java/edu/wpi/first/wpilibj/PWM.java b/wpilibj/src/athena/java/edu/wpi/first/wpilibj/PWM.java index a08d1ee7a6..654d43e931 100644 --- a/wpilibj/src/athena/java/edu/wpi/first/wpilibj/PWM.java +++ b/wpilibj/src/athena/java/edu/wpi/first/wpilibj/PWM.java @@ -140,7 +140,7 @@ public class PWM extends SensorBase implements LiveWindowSendable { double min) { PWMJNI.setPWMConfig(m_handle, max, deadbandMax, center, deadbandMax, min); } - + /** * Gets the bounds on the PWM pulse widths. This Gets the bounds on the PWM values for a * particular type of controller. The values determine the upper and lower speeds as well @@ -237,7 +237,7 @@ public class PWM extends SensorBase implements LiveWindowSendable { public int getRaw() { return PWMJNI.getPWMRaw(m_handle); } - + /** * Temporarily disables the PWM output. The next set call will reenable * the output. diff --git a/wpilibj/src/athena/java/edu/wpi/first/wpilibj/PWMConfigDataResult.java b/wpilibj/src/athena/java/edu/wpi/first/wpilibj/PWMConfigDataResult.java index e8e0630ad7..f5c4be895e 100644 --- a/wpilibj/src/athena/java/edu/wpi/first/wpilibj/PWMConfigDataResult.java +++ b/wpilibj/src/athena/java/edu/wpi/first/wpilibj/PWMConfigDataResult.java @@ -19,31 +19,31 @@ public class PWMConfigDataResult { this.deadbandMin = deadbandMin; this.min = min; } - + /** * The maximum PWM value. */ @SuppressWarnings("MemberName") public int max; - + /** * The deadband maximum PWM value. */ @SuppressWarnings("MemberName") public int deadbandMax; - + /** * The center PWM value. */ @SuppressWarnings("MemberName") public int center; - + /** * The deadband minimum PWM value. */ @SuppressWarnings("MemberName") public int deadbandMin; - + /** * The minimum PWM value. */ diff --git a/wpilibj/src/athena/java/edu/wpi/first/wpilibj/hal/PWMJNI.java b/wpilibj/src/athena/java/edu/wpi/first/wpilibj/hal/PWMJNI.java index bc933a59eb..ad8daef415 100644 --- a/wpilibj/src/athena/java/edu/wpi/first/wpilibj/hal/PWMJNI.java +++ b/wpilibj/src/athena/java/edu/wpi/first/wpilibj/hal/PWMJNI.java @@ -14,13 +14,13 @@ public class PWMJNI extends DIOJNI { public static native int initializePWMPort(int halPortHandle); public static native void freePWMPort(int pwmPortHandle); - - public static native void setPWMConfigRaw(int pwmPortHandle, int maxPwm, - int deadbandMaxPwm, int centerPwm, + + public static native void setPWMConfigRaw(int pwmPortHandle, int maxPwm, + int deadbandMaxPwm, int centerPwm, int deadbandMinPwm, int minPwm); - - public static native void setPWMConfig(int pwmPortHandle, double maxPwm, - double deadbandMaxPwm, double centerPwm, + + public static native void setPWMConfig(int pwmPortHandle, double maxPwm, + double deadbandMaxPwm, double centerPwm, double deadbandMinPwm, double minPwm); public static native PWMConfigDataResult getPWMConfigRaw(int pwmPortHandle); @@ -30,17 +30,17 @@ public class PWMJNI extends DIOJNI { public static native boolean getPWMEliminateDeadband(int pwmPortHandle); public static native void setPWMRaw(int pwmPortHandle, short value); - + public static native void setPWMSpeed(int pwmPortHandle, float speed); - + public static native void setPWMPosition(int pwmPortHandle, float position); public static native short getPWMRaw(int pwmPortHandle); - + public static native float getPWMSpeed(int pwmPortHandle); - + public static native float getPWMPosition(int pwmPortHandle); - + public static native void setPWMDisabled(int pwmPortHandle); public static native void latchPWMZero(int pwmPortHandle);