Browse Source

remove all <cmath> usage

* the NuttX c++ library is incomplete, let's avoid including it until we have a real standard library in place
sbg
Daniel Agar 5 years ago committed by GitHub
parent
commit
a8ea55d9b6
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
  1. 4
      platforms/nuttx/src/px4/nxp/kinetis/tone_alarm/ToneAlarmInterface.cpp
  2. 4
      platforms/nuttx/src/px4/stm/stm32_common/tone_alarm/ToneAlarmInterfacePWM.cpp
  3. 2
      src/drivers/linux_pwm_out/linux_pwm_out.cpp
  4. 2
      src/drivers/snapdragon_pwm_out/snapdragon_pwm_out.cpp
  5. 2
      src/drivers/tap_esc/tap_esc.cpp
  6. 2
      src/drivers/uavcan/sensors/baro.cpp
  7. 2
      src/drivers/uavcan/uavcan_drivers/kinetis/driver/src/uc_kinetis_clock.cpp
  8. 2
      src/drivers/uavcan/uavcan_drivers/stm32/driver/src/uc_stm32_clock.cpp
  9. 2
      src/lib/mathlib/math/filter/LowPassFilter2p.cpp
  10. 2
      src/lib/mathlib/math/filter/LowPassFilter2pVector3f.cpp
  11. 2
      src/lib/mixer/MultirotorMixer/test_mixer_multirotor.cpp
  12. 4
      src/modules/commander/Commander.cpp
  13. 2
      src/modules/commander/airspeed_calibration.cpp
  14. 2
      src/modules/commander/gyro_calibration.cpp
  15. 2
      src/modules/commander/mag_calibration.cpp
  16. 2
      src/modules/land_detector/MulticopterLandDetector.cpp
  17. 4
      src/modules/mavlink/mavlink_mission.cpp

4
platforms/nuttx/src/px4/nxp/kinetis/tone_alarm/ToneAlarmInterface.cpp

@ -43,7 +43,7 @@ @@ -43,7 +43,7 @@
#include <px4_platform_common/defines.h>
#include <systemlib/px4_macros.h>
#include <cmath>
#include <math.h>
#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) @@ -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.

4
platforms/nuttx/src/px4/stm/stm32_common/tone_alarm/ToneAlarmInterfacePWM.cpp

@ -34,7 +34,7 @@ @@ -34,7 +34,7 @@
#include <drivers/device/device.h>
#include <drivers/drv_tone_alarm.h>
#include <px4_platform_common/defines.h>
#include <cmath>
#include <math.h>
/* 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) @@ -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.)

2
src/drivers/linux_pwm_out/linux_pwm_out.cpp

@ -36,7 +36,7 @@ @@ -36,7 +36,7 @@
#include <stdlib.h>
#include <string.h>
#include <cmath>
#include <math.h>
#include <px4_platform_common/tasks.h>
#include <px4_platform_common/getopt.h>

2
src/drivers/snapdragon_pwm_out/snapdragon_pwm_out.cpp

@ -37,7 +37,7 @@ @@ -37,7 +37,7 @@
#include <px4_platform_common/getopt.h>
#include <px4_platform_common/posix.h>
#include <errno.h>
#include <cmath> // NAN
#include <math.h> // NAN
#include <string.h>
#include <uORB/Subscription.hpp>

2
src/drivers/tap_esc/tap_esc.cpp

@ -40,7 +40,7 @@ @@ -40,7 +40,7 @@
#include <px4_platform_common/posix.h>
#include <errno.h>
#include <cmath> // NAN
#include <math.h> // NAN
#include <cstring>
#include <lib/mathlib/mathlib.h>

2
src/drivers/uavcan/sensors/baro.cpp

@ -37,7 +37,7 @@ @@ -37,7 +37,7 @@
#include <drivers/drv_hrt.h>
#include "baro.hpp"
#include <cmath>
#include <math.h>
const char *const UavcanBarometerBridge::NAME = "baro";

2
src/drivers/uavcan/uavcan_drivers/kinetis/driver/src/uc_kinetis_clock.cpp

@ -9,7 +9,7 @@ @@ -9,7 +9,7 @@
#if UAVCAN_KINETIS_TIMER_NUMBER
# include <cassert>
# include <cmath>
# include <math.h>
/*
* Timer instance

2
src/drivers/uavcan/uavcan_drivers/stm32/driver/src/uc_stm32_clock.cpp

@ -9,7 +9,7 @@ @@ -9,7 +9,7 @@
#if UAVCAN_STM32_TIMER_NUMBER
#include <cassert>
#include <cmath>
#include <math.h>
/*
* Timer instance

2
src/lib/mathlib/math/filter/LowPassFilter2p.cpp

@ -35,7 +35,7 @@ @@ -35,7 +35,7 @@
#include <px4_platform_common/defines.h>
#include <cmath>
#include <math.h>
namespace math
{

2
src/lib/mathlib/math/filter/LowPassFilter2pVector3f.cpp

@ -35,7 +35,7 @@ @@ -35,7 +35,7 @@
#include <px4_platform_common/defines.h>
#include <cmath>
#include <math.h>
namespace math
{

2
src/lib/mixer/MultirotorMixer/test_mixer_multirotor.cpp

@ -39,7 +39,7 @@ @@ -39,7 +39,7 @@
#include "MultirotorMixer.hpp"
#include <cstdio>
#include <cmath>
#include <math.h>
static const unsigned output_max = 16;
static float actuator_controls[output_max] {};

4
src/modules/commander/Commander.cpp

@ -76,7 +76,7 @@ @@ -76,7 +76,7 @@
#include <circuit_breaker/circuit_breaker.h>
#include <systemlib/mavlink_log.h>
#include <cmath>
#include <math.h>
#include <float.h>
#include <cstring>
@ -768,7 +768,7 @@ Commander::handle_command(vehicle_status_s *status_local, const vehicle_command_ @@ -768,7 +768,7 @@ Commander::handle_command(vehicle_status_s *status_local, const vehicle_command_
bool cmd_arms = (static_cast<int>(cmd.param1 + 0.5f) == 1);
// Arm/disarm is enforced when param2 is set to a magic number.
const bool enforce = (static_cast<int>(std::round(cmd.param2)) == 21196);
const bool enforce = (static_cast<int>(roundf(cmd.param2)) == 21196);
if (!enforce) {
if (!land_detector.landed && !is_ground_rover(&status)) {

2
src/modules/commander/airspeed_calibration.cpp

@ -48,7 +48,7 @@ @@ -48,7 +48,7 @@
#include <unistd.h>
#include <fcntl.h>
#include <poll.h>
#include <cmath>
#include <math.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_airspeed.h>
#include <uORB/topics/differential_pressure.h>

2
src/modules/commander/gyro_calibration.cpp

@ -50,7 +50,7 @@ @@ -50,7 +50,7 @@
#include <unistd.h>
#include <fcntl.h>
#include <poll.h>
#include <cmath>
#include <math.h>
#include <string.h>
#include <drivers/drv_hrt.h>
#include <uORB/topics/sensor_combined.h>

2
src/modules/commander/mag_calibration.cpp

@ -50,7 +50,7 @@ @@ -50,7 +50,7 @@
#include <stdlib.h>
#include <string.h>
#include <poll.h>
#include <cmath>
#include <math.h>
#include <fcntl.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_accel.h>

2
src/modules/land_detector/MulticopterLandDetector.cpp

@ -61,7 +61,7 @@ @@ -61,7 +61,7 @@
* @author Julian Oes <julian@oes.ch>
*/
#include <cmath>
#include <math.h>
#include <mathlib/mathlib.h>
#include <matrix/math.hpp>

4
src/modules/mavlink/mavlink_mission.cpp

@ -1546,8 +1546,8 @@ MavlinkMissionManager::format_mavlink_mission_item(const struct mission_item_s * @@ -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_int_t *>(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;

Loading…
Cancel
Save