mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 15:38:29 -04:00
AP_Math: Created CentiDegreesToRadians
This commit is contained in:
parent
f89923fcbe
commit
9a3f6ae9c7
@ -42,6 +42,7 @@ static const double RAD_TO_DEG_DOUBLE = 1 / DEG_TO_RAD_DOUBLE;
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define RadiansToCentiDegrees(x) (static_cast<float>(x) * RAD_TO_DEG * static_cast<float>(100))
|
#define RadiansToCentiDegrees(x) (static_cast<float>(x) * RAD_TO_DEG * static_cast<float>(100))
|
||||||
|
#define CentiDegreesToRadians(x) (static_cast<float>(x) * DEG_TO_RAD * 0.01f)
|
||||||
|
|
||||||
// acceleration due to gravity in m/s/s
|
// acceleration due to gravity in m/s/s
|
||||||
#define GRAVITY_MSS 9.80665f
|
#define GRAVITY_MSS 9.80665f
|
||||||
|
Loading…
Reference in New Issue
Block a user