mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-12 02:48:28 -04:00
navigation.pde: Put the new calc_GPS_velocity method in a compiler if that checks the new RETRO_LOITER_MODE config value (saves space and ensures its not being used unless retro loiter mode is enabled)
This commit is contained in:
parent
9181eedf5a
commit
4430f75344
@ -90,12 +90,14 @@ static void calc_XY_velocity(){
|
|||||||
last_latitude = g_gps->latitude;
|
last_latitude = g_gps->latitude;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if RETRO_LOITER_MODE == ENABLED
|
||||||
static void calc_GPS_velocity()
|
static void calc_GPS_velocity()
|
||||||
{
|
{
|
||||||
float temp = radians((float)g_gps->ground_course/100.0);
|
float temp = radians((float)g_gps->ground_course/100.0);
|
||||||
x_actual_speed = (float)g_gps->ground_speed * sin(temp);
|
x_actual_speed = (float)g_gps->ground_speed * sin(temp);
|
||||||
y_actual_speed = (float)g_gps->ground_speed * cos(temp);
|
y_actual_speed = (float)g_gps->ground_speed * cos(temp);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
static void calc_location_error(struct Location *next_loc)
|
static void calc_location_error(struct Location *next_loc)
|
||||||
{
|
{
|
||||||
|
Loading…
Reference in New Issue
Block a user