mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
removed GPS ground speed calc - was causing some funny business during the transition.
This commit is contained in:
parent
b2d932136a
commit
c20c04ed24
@ -50,11 +50,12 @@ static void calc_XY_velocity(){
|
|||||||
last_longitude = g_gps->longitude;
|
last_longitude = g_gps->longitude;
|
||||||
last_latitude = g_gps->latitude;
|
last_latitude = g_gps->latitude;
|
||||||
|
|
||||||
if(g_gps->ground_speed > 150){
|
/*if(g_gps->ground_speed > 150){
|
||||||
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);
|
||||||
}
|
}*/
|
||||||
|
|
||||||
|
|
||||||
#if INERTIAL_NAV == ENABLED
|
#if INERTIAL_NAV == ENABLED
|
||||||
// inertial_nav
|
// inertial_nav
|
||||||
|
Loading…
Reference in New Issue
Block a user