mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
AP_Math: rename macros to avoid conflicts
these macros were also defined in NuttX in clock.h
This commit is contained in:
parent
e51bbcebec
commit
607220d12b
@ -183,32 +183,32 @@ static inline auto MAX(const A &one, const B &two) -> decltype(one > two ? one :
|
|||||||
|
|
||||||
inline uint32_t hz_to_nsec(uint32_t freq)
|
inline uint32_t hz_to_nsec(uint32_t freq)
|
||||||
{
|
{
|
||||||
return NSEC_PER_SEC / freq;
|
return AP_NSEC_PER_SEC / freq;
|
||||||
}
|
}
|
||||||
|
|
||||||
inline uint32_t nsec_to_hz(uint32_t nsec)
|
inline uint32_t nsec_to_hz(uint32_t nsec)
|
||||||
{
|
{
|
||||||
return NSEC_PER_SEC / nsec;
|
return AP_NSEC_PER_SEC / nsec;
|
||||||
}
|
}
|
||||||
|
|
||||||
inline uint32_t usec_to_nsec(uint32_t usec)
|
inline uint32_t usec_to_nsec(uint32_t usec)
|
||||||
{
|
{
|
||||||
return usec * NSEC_PER_USEC;
|
return usec * AP_NSEC_PER_USEC;
|
||||||
}
|
}
|
||||||
|
|
||||||
inline uint32_t nsec_to_usec(uint32_t nsec)
|
inline uint32_t nsec_to_usec(uint32_t nsec)
|
||||||
{
|
{
|
||||||
return nsec / NSEC_PER_USEC;
|
return nsec / AP_NSEC_PER_USEC;
|
||||||
}
|
}
|
||||||
|
|
||||||
inline uint32_t hz_to_usec(uint32_t freq)
|
inline uint32_t hz_to_usec(uint32_t freq)
|
||||||
{
|
{
|
||||||
return USEC_PER_SEC / freq;
|
return AP_USEC_PER_SEC / freq;
|
||||||
}
|
}
|
||||||
|
|
||||||
inline uint32_t usec_to_hz(uint32_t usec)
|
inline uint32_t usec_to_hz(uint32_t usec)
|
||||||
{
|
{
|
||||||
return USEC_PER_SEC / usec;
|
return AP_USEC_PER_SEC / usec;
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -64,10 +64,14 @@ static const double WGS84_B = (WGS84_A * (1 - WGS84_F));
|
|||||||
// Eccentricity of the Earth
|
// Eccentricity of the Earth
|
||||||
static const double WGS84_E = (sqrt(2 * WGS84_F - WGS84_F * WGS84_F));
|
static const double WGS84_E = (sqrt(2 * WGS84_F - WGS84_F * WGS84_F));
|
||||||
|
|
||||||
#define NSEC_PER_SEC 1000000000ULL
|
/*
|
||||||
#define NSEC_PER_USEC 1000ULL
|
use AP_ prefix to prevent conflict with OS headers, such as NuttX
|
||||||
#define USEC_PER_SEC 1000000ULL
|
clock.h
|
||||||
#define USEC_PER_MSEC 1000ULL
|
*/
|
||||||
#define MSEC_PER_SEC 1000ULL
|
#define AP_NSEC_PER_SEC 1000000000ULL
|
||||||
#define SEC_PER_WEEK (7ULL * 86400ULL)
|
#define AP_NSEC_PER_USEC 1000ULL
|
||||||
#define MSEC_PER_WEEK (SEC_PER_WEEK * MSEC_PER_SEC)
|
#define AP_USEC_PER_SEC 1000000ULL
|
||||||
|
#define AP_USEC_PER_MSEC 1000ULL
|
||||||
|
#define AP_MSEC_PER_SEC 1000ULL
|
||||||
|
#define AP_SEC_PER_WEEK (7ULL * 86400ULL)
|
||||||
|
#define AP_MSEC_PER_WEEK (AP_SEC_PER_WEEK * AP_MSEC_PER_SEC)
|
||||||
|
Loading…
Reference in New Issue
Block a user