mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 08:23:56 -04:00
AP_Math: fix for HAL_SITL rename
This commit is contained in:
parent
ef527d9daa
commit
eca675c556
@ -39,7 +39,7 @@ float fast_atan(float v)
|
||||
return (v*(1.6867629106f + v2*0.4378497304f)/(1.6867633134f + v2));
|
||||
}
|
||||
|
||||
#if HAL_CPU_CLASS < HAL_CPU_CLASS_75 || CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
|
||||
#if HAL_CPU_CLASS < HAL_CPU_CLASS_75 || CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#define FAST_ATAN2_PIBY2_FLOAT 1.5707963f
|
||||
// fast_atan2 - faster version of atan2
|
||||
// 126 us on AVR cpu vs 199 for regular atan2
|
||||
|
@ -9,7 +9,7 @@
|
||||
#include <AP_Progmem.h>
|
||||
#include <AP_Param.h>
|
||||
#include <AP_HAL_AVR.h>
|
||||
#include <AP_HAL_AVR_SITL.h>
|
||||
#include <AP_HAL_SITL.h>
|
||||
#include <AP_HAL_Empty.h>
|
||||
#include <AP_HAL_PX4.h>
|
||||
#include <AP_HAL_Linux.h>
|
||||
|
@ -22,7 +22,7 @@
|
||||
#include <AP_Declination.h>
|
||||
|
||||
#include <AP_HAL_AVR.h>
|
||||
#include <AP_HAL_AVR_SITL.h>
|
||||
#include <AP_HAL_SITL.h>
|
||||
#include <AP_HAL_Empty.h>
|
||||
#include <AP_HAL_Linux.h>
|
||||
#include <AP_AHRS.h>
|
||||
|
@ -8,7 +8,7 @@
|
||||
#include <AP_Progmem.h>
|
||||
#include <AP_Param.h>
|
||||
#include <AP_HAL_AVR.h>
|
||||
#include <AP_HAL_AVR_SITL.h>
|
||||
#include <AP_HAL_SITL.h>
|
||||
#include <AP_HAL_Empty.h>
|
||||
#include <AP_HAL_PX4.h>
|
||||
#include <AP_HAL_Linux.h>
|
||||
|
Loading…
Reference in New Issue
Block a user