diff --git a/platforms/nuttx/src/px4/nxp/kinetis/tone_alarm/ToneAlarmInterface.cpp b/platforms/nuttx/src/px4/nxp/kinetis/tone_alarm/ToneAlarmInterface.cpp index e9df8ccf92..df36cd725c 100644 --- a/platforms/nuttx/src/px4/nxp/kinetis/tone_alarm/ToneAlarmInterface.cpp +++ b/platforms/nuttx/src/px4/nxp/kinetis/tone_alarm/ToneAlarmInterface.cpp @@ -43,7 +43,7 @@ #include #include -#include +#include #define CAT3_(A, B, C) A##B##C #define CAT3(A, B, C) CAT3_(A, B, C) @@ -166,7 +166,7 @@ void start_note(unsigned frequency) float signal_period = (1.0f / frequency) * 0.5f; // Calculate the hardware clock divisor rounded to the nearest integer. - unsigned int divisor = std::round(signal_period * TONE_ALARM_CLOCK); + unsigned int divisor = roundf(signal_period * TONE_ALARM_CLOCK); rCNT = 0; rMOD = divisor; // Load new signal switching period. diff --git a/platforms/nuttx/src/px4/stm/stm32_common/tone_alarm/ToneAlarmInterfacePWM.cpp b/platforms/nuttx/src/px4/stm/stm32_common/tone_alarm/ToneAlarmInterfacePWM.cpp index cf07376ede..6ba13e65ac 100644 --- a/platforms/nuttx/src/px4/stm/stm32_common/tone_alarm/ToneAlarmInterfacePWM.cpp +++ b/platforms/nuttx/src/px4/stm/stm32_common/tone_alarm/ToneAlarmInterfacePWM.cpp @@ -34,7 +34,7 @@ #include #include #include -#include +#include /* Check that tone alarm and HRT timers are different */ #if defined(TONE_ALARM_TIMER) && defined(HRT_TIMER) @@ -288,7 +288,7 @@ void start_note(unsigned frequency) float signal_period = (1.0f / frequency) * 0.5f; // Calculate the hardware clock divisor rounded to the nearest integer. - unsigned int divisor = std::round(signal_period * TONE_ALARM_CLOCK); + unsigned int divisor = roundf(signal_period * TONE_ALARM_CLOCK); // Pick the lowest prescaler value that we can use. // (Note that the effective prescale value is 1 greater.) diff --git a/src/drivers/linux_pwm_out/linux_pwm_out.cpp b/src/drivers/linux_pwm_out/linux_pwm_out.cpp index 603ac9c87b..482c376194 100644 --- a/src/drivers/linux_pwm_out/linux_pwm_out.cpp +++ b/src/drivers/linux_pwm_out/linux_pwm_out.cpp @@ -36,7 +36,7 @@ #include #include -#include +#include #include #include diff --git a/src/drivers/snapdragon_pwm_out/snapdragon_pwm_out.cpp b/src/drivers/snapdragon_pwm_out/snapdragon_pwm_out.cpp index a871ded4d6..6a600339f2 100644 --- a/src/drivers/snapdragon_pwm_out/snapdragon_pwm_out.cpp +++ b/src/drivers/snapdragon_pwm_out/snapdragon_pwm_out.cpp @@ -37,7 +37,7 @@ #include #include #include -#include // NAN +#include // NAN #include #include diff --git a/src/drivers/tap_esc/tap_esc.cpp b/src/drivers/tap_esc/tap_esc.cpp index 911be2bb0a..fe50925929 100644 --- a/src/drivers/tap_esc/tap_esc.cpp +++ b/src/drivers/tap_esc/tap_esc.cpp @@ -40,7 +40,7 @@ #include #include -#include // NAN +#include // NAN #include #include diff --git a/src/drivers/uavcan/sensors/baro.cpp b/src/drivers/uavcan/sensors/baro.cpp index 6a515a6a55..22236e9e1f 100644 --- a/src/drivers/uavcan/sensors/baro.cpp +++ b/src/drivers/uavcan/sensors/baro.cpp @@ -37,7 +37,7 @@ #include #include "baro.hpp" -#include +#include const char *const UavcanBarometerBridge::NAME = "baro"; diff --git a/src/drivers/uavcan/uavcan_drivers/kinetis/driver/src/uc_kinetis_clock.cpp b/src/drivers/uavcan/uavcan_drivers/kinetis/driver/src/uc_kinetis_clock.cpp index fd57f8b39f..9560284094 100644 --- a/src/drivers/uavcan/uavcan_drivers/kinetis/driver/src/uc_kinetis_clock.cpp +++ b/src/drivers/uavcan/uavcan_drivers/kinetis/driver/src/uc_kinetis_clock.cpp @@ -9,7 +9,7 @@ #if UAVCAN_KINETIS_TIMER_NUMBER # include -# include +# include /* * Timer instance diff --git a/src/drivers/uavcan/uavcan_drivers/stm32/driver/src/uc_stm32_clock.cpp b/src/drivers/uavcan/uavcan_drivers/stm32/driver/src/uc_stm32_clock.cpp index 3e4fb715c7..c2e0216ea2 100644 --- a/src/drivers/uavcan/uavcan_drivers/stm32/driver/src/uc_stm32_clock.cpp +++ b/src/drivers/uavcan/uavcan_drivers/stm32/driver/src/uc_stm32_clock.cpp @@ -9,7 +9,7 @@ #if UAVCAN_STM32_TIMER_NUMBER #include -#include +#include /* * Timer instance diff --git a/src/lib/mathlib/math/filter/LowPassFilter2p.cpp b/src/lib/mathlib/math/filter/LowPassFilter2p.cpp index 2be5227a90..55e8cdc513 100644 --- a/src/lib/mathlib/math/filter/LowPassFilter2p.cpp +++ b/src/lib/mathlib/math/filter/LowPassFilter2p.cpp @@ -35,7 +35,7 @@ #include -#include +#include namespace math { diff --git a/src/lib/mathlib/math/filter/LowPassFilter2pVector3f.cpp b/src/lib/mathlib/math/filter/LowPassFilter2pVector3f.cpp index fb4845d19a..1619d4564d 100644 --- a/src/lib/mathlib/math/filter/LowPassFilter2pVector3f.cpp +++ b/src/lib/mathlib/math/filter/LowPassFilter2pVector3f.cpp @@ -35,7 +35,7 @@ #include -#include +#include namespace math { diff --git a/src/lib/mixer/MultirotorMixer/test_mixer_multirotor.cpp b/src/lib/mixer/MultirotorMixer/test_mixer_multirotor.cpp index 46af77012f..87a1ebc3ed 100644 --- a/src/lib/mixer/MultirotorMixer/test_mixer_multirotor.cpp +++ b/src/lib/mixer/MultirotorMixer/test_mixer_multirotor.cpp @@ -39,7 +39,7 @@ #include "MultirotorMixer.hpp" #include -#include +#include static const unsigned output_max = 16; static float actuator_controls[output_max] {}; diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp index 09f9b64363..811e24952b 100644 --- a/src/modules/commander/Commander.cpp +++ b/src/modules/commander/Commander.cpp @@ -76,7 +76,7 @@ #include #include -#include +#include #include #include @@ -768,7 +768,7 @@ Commander::handle_command(vehicle_status_s *status_local, const vehicle_command_ bool cmd_arms = (static_cast(cmd.param1 + 0.5f) == 1); // Arm/disarm is enforced when param2 is set to a magic number. - const bool enforce = (static_cast(std::round(cmd.param2)) == 21196); + const bool enforce = (static_cast(roundf(cmd.param2)) == 21196); if (!enforce) { if (!land_detector.landed && !is_ground_rover(&status)) { diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp index 21e1cd9861..98f816b48a 100644 --- a/src/modules/commander/airspeed_calibration.cpp +++ b/src/modules/commander/airspeed_calibration.cpp @@ -48,7 +48,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/src/modules/commander/gyro_calibration.cpp b/src/modules/commander/gyro_calibration.cpp index ed4f18b9c4..1d28f5aad8 100644 --- a/src/modules/commander/gyro_calibration.cpp +++ b/src/modules/commander/gyro_calibration.cpp @@ -50,7 +50,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/src/modules/commander/mag_calibration.cpp b/src/modules/commander/mag_calibration.cpp index a1a7355cf4..cbd1592178 100644 --- a/src/modules/commander/mag_calibration.cpp +++ b/src/modules/commander/mag_calibration.cpp @@ -50,7 +50,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/src/modules/land_detector/MulticopterLandDetector.cpp b/src/modules/land_detector/MulticopterLandDetector.cpp index 96a78c3fd8..e682753aab 100644 --- a/src/modules/land_detector/MulticopterLandDetector.cpp +++ b/src/modules/land_detector/MulticopterLandDetector.cpp @@ -61,7 +61,7 @@ * @author Julian Oes */ -#include +#include #include #include diff --git a/src/modules/mavlink/mavlink_mission.cpp b/src/modules/mavlink/mavlink_mission.cpp index 857ec0aa2f..12ba2f6b53 100644 --- a/src/modules/mavlink/mavlink_mission.cpp +++ b/src/modules/mavlink/mavlink_mission.cpp @@ -1546,8 +1546,8 @@ MavlinkMissionManager::format_mavlink_mission_item(const struct mission_item_s * mavlink_mission_item_int_t *item_int = reinterpret_cast(mavlink_mission_item); - item_int->x = std::round(mission_item->lat * 1e7); - item_int->y = std::round(mission_item->lon * 1e7); + item_int->x = round(mission_item->lat * 1e7); + item_int->y = round(mission_item->lon * 1e7); } else { mavlink_mission_item->x = (float)mission_item->lat;