Global: start using cmath instead of math.h

This commit is contained in:
Ricardo de Almeida Gonzaga 2016-03-31 18:43:36 -03:00 committed by Lucas De Marchi
parent 60d141c717
commit 5bd034a5a8
36 changed files with 36 additions and 36 deletions

View File

@ -21,7 +21,7 @@
#define THISFIRMWARE "ArduRover v3.0.0"
#define FIRMWARE_VERSION 3,0,0,FIRMWARE_VERSION_TYPE_OFFICIAL
#include <math.h>
#include <cmath>
#include <stdarg.h>
// Libraries

View File

@ -26,7 +26,7 @@
// Header includes
////////////////////////////////////////////////////////////////////////////////
#include <math.h>
#include <cmath>
#include <stdarg.h>
#include <stdio.h>

View File

@ -26,7 +26,7 @@
// Header includes
////////////////////////////////////////////////////////////////////////////////
#include <math.h>
#include <cmath>
#include <stdio.h>
#include <stdarg.h>

View File

@ -30,7 +30,7 @@
// Header includes
////////////////////////////////////////////////////////////////////////////////
#include <math.h>
#include <cmath>
#include <stdarg.h>
#include <stdio.h>

View File

@ -5,7 +5,7 @@
Andrew Tridgell September 2011
*/
#include <math.h>
#include <cmath>
#include <AP_HAL/AP_HAL.h>
#include <AP_Common/AP_Common.h>

View File

@ -49,7 +49,7 @@
#include <err.h>
#include <fcntl.h>
#include <math.h>
#include <cmath>
#include <pthread.h>
#include <signal.h>
#include <string.h>

View File

@ -7,7 +7,7 @@
#include <AP_Common/AP_Common.h>
#include <AP_Param/AP_Param.h>
#include <stdlib.h>
#include <math.h>
#include <cmath>
#include "AC_PID.h"
#define AC_PID_LEAK_MIN 500.0 // Default I-term Leak Minimum

View File

@ -7,7 +7,7 @@
#include <AP_Common/AP_Common.h>
#include <AP_Param/AP_Param.h>
#include <stdlib.h>
#include <math.h>
#include <cmath>
/// @class AC_P
/// @brief Object managing one P controller

View File

@ -7,7 +7,7 @@
#include <AP_Common/AP_Common.h>
#include <AP_Param/AP_Param.h>
#include <stdlib.h>
#include <math.h>
#include <cmath>
#include <DataFlash/DataFlash.h>
#define AC_PID_FILT_HZ_DEFAULT 20.0f // default input filter frequency

View File

@ -7,7 +7,7 @@
#include <AP_Common/AP_Common.h>
#include <AP_Param/AP_Param.h>
#include <stdlib.h>
#include <math.h>
#include <cmath>
#define AC_PI_2D_FILT_HZ_DEFAULT 20.0f // default input filter frequency
#define AC_PI_2D_FILT_HZ_MIN 0.01f // minimum input filter frequency

View File

@ -5,7 +5,7 @@
#include <AP_Common/AP_Common.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <DataFlash/DataFlash.h>
#include <math.h>
#include <cmath>
class AP_YawController {
public:

View File

@ -4,7 +4,7 @@
* Code by Jordi Muñoz and Jose Julio. DIYDrones.com
*/
#include <math.h>
#include <cmath>
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>

View File

@ -25,7 +25,7 @@
*/
#include "AP_Declination.h"
#include <math.h>
#include <cmath>
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>

View File

@ -28,7 +28,7 @@
#include <uORB/uORB.h>
#include <math.h>
#include <cmath>
extern const AP_HAL::HAL& hal;

View File

@ -39,7 +39,7 @@
#include "print_vprintf.h"
#include <math.h>
#include <cmath>
#include <stdarg.h>
#include <string.h>

View File

@ -7,7 +7,7 @@
#include <AP_Common/AP_Common.h>
#include <AP_ADC/AP_ADC.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
#include <math.h>
#include <cmath>
#include <AP_Param/AP_Param.h>
#include <AP_Math/AP_Math.h>
#include <AP_HAL/AP_HAL.h>

View File

@ -42,7 +42,7 @@
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI
#include "Flow_PX4.h"
#include <math.h>
#include <cmath>
#include <stdbool.h>
#include <stdio.h>
#include <stdlib.h>

View File

@ -24,7 +24,7 @@
#include <unistd.h>
#include <linux/limits.h>
#include <string.h>
#include <math.h>
#include <cmath>
#include <stdlib.h>
#include "Heat_Pwm.h"

View File

@ -13,7 +13,7 @@
#include <stdlib.h>
#include <stdio.h>
#include <stdint.h>
#include <math.h>
#include <cmath>
#define PCA9685_RA_MODE1 0x00
#define PCA9685_RA_MODE2 0x01

View File

@ -13,7 +13,7 @@
#include <stdlib.h>
#include <stdio.h>
#include <stdint.h>
#include <math.h>
#include <cmath>
#include "px4io_protocol.h"
using namespace Linux;

View File

@ -21,7 +21,7 @@ extern const AP_HAL::HAL& hal;
#include <stdio.h>
#include <stdlib.h>
#include <stdint.h>
#include <math.h>
#include <cmath>
/*
setup the barometer with new input

View File

@ -21,7 +21,7 @@ extern const AP_HAL::HAL& hal;
#include <stdio.h>
#include <stdlib.h>
#include <stdint.h>
#include <math.h>
#include <cmath>
#define MAX_OPTFLOW_DELAY 20
static uint8_t next_optflow_index;

View File

@ -7,7 +7,7 @@
#include <AP_Common/AP_Common.h>
#include <AP_Param/AP_Param.h>
#include <math.h>
#include <cmath>
#include <stdint.h>
#include "rotations.h"

View File

@ -1,6 +1,6 @@
#pragma once
#include <math.h>
#include <cmath>
#include <AP_HAL/AP_HAL.h>

View File

@ -18,7 +18,7 @@
// Refactored by Jonathan Challinger
#pragma once
#include <math.h>
#include <cmath>
#if MATH_CHECK_INDEXES
#include <assert.h>
#endif

View File

@ -30,7 +30,7 @@
****************************************/
#pragma once
#include <math.h>
#include <cmath>
template <typename T>
struct Vector2

View File

@ -48,7 +48,7 @@
****************************************/
#pragma once
#include <math.h>
#include <cmath>
#include <float.h>
#include <string.h>

View File

@ -15,7 +15,7 @@
*/
#pragma once
#include <math.h>
#include <cmath>
#include <string.h>
#if MATH_CHECK_INDEXES
#include <assert.h>

View File

@ -24,7 +24,7 @@
/// @brief The AP variable store.
#include "AP_Param.h"
#include <math.h>
#include <cmath>
#include <string.h>
#include <AP_Common/AP_Common.h>

View File

@ -23,7 +23,7 @@
#include <stddef.h>
#include <string.h>
#include <stdint.h>
#include <math.h>
#include <cmath>
#include <AP_HAL/AP_HAL.h>
#include <StorageManager/StorageManager.h>

View File

@ -30,7 +30,7 @@
#include <uORB/topics/pwm_input.h>
#include <stdio.h>
#include <errno.h>
#include <math.h>
#include <cmath>
#define PWM_LOGGING 0

View File

@ -30,7 +30,7 @@
#include <uORB/topics/pwm_input.h>
#include <stdio.h>
#include <errno.h>
#include <math.h>
#include <cmath>
extern const AP_HAL::HAL& hal;

View File

@ -17,7 +17,7 @@
#pragma once
#include <AP_Math/AP_Math.h>
#include <math.h>
#include <cmath>
#include <inttypes.h>

View File

@ -3,7 +3,7 @@
/// @file PID.cpp
/// @brief Generic PID algorithm
#include <math.h>
#include <cmath>
#include "PID.h"
#include <AP_HAL/AP_HAL.h>

View File

@ -7,7 +7,7 @@
#include <AP_Common/AP_Common.h>
#include <AP_Param/AP_Param.h>
#include <stdlib.h>
#include <math.h> // for fabs()
#include <cmath>
/// @class PID
/// @brief Object managing one PID control

View File

@ -21,7 +21,7 @@
*/
#include <stdlib.h>
#include <math.h>
#include <cmath>
#include <AP_HAL/AP_HAL.h>
extern const AP_HAL::HAL& hal;