mirror of https://github.com/ArduPilot/ardupilot
AP_Math: move definition of HAL_WITH_POSTYPE_DOUBLE into AP_HAL_Boards.h
other libraries need to know if we are doing double-precision offsets
This commit is contained in:
parent
d70f5b92e0
commit
0fc6fc4e9c
|
@ -4,10 +4,6 @@
|
||||||
#include "vector2.h"
|
#include "vector2.h"
|
||||||
#include "vector3.h"
|
#include "vector3.h"
|
||||||
|
|
||||||
#ifndef HAL_WITH_POSTYPE_DOUBLE
|
|
||||||
#define HAL_WITH_POSTYPE_DOUBLE BOARD_FLASH_SIZE > 1024
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if HAL_WITH_POSTYPE_DOUBLE
|
#if HAL_WITH_POSTYPE_DOUBLE
|
||||||
typedef double postype_t;
|
typedef double postype_t;
|
||||||
typedef Vector2d Vector2p;
|
typedef Vector2d Vector2p;
|
||||||
|
|
Loading…
Reference in New Issue