mirror of https://github.com/ArduPilot/ardupilot
ArduCopter - bug fix to calc_XY_velocity (was using uninitialised last_longitutde and last_latitude for speed calculations)
This commit is contained in:
parent
6305312be7
commit
91b2b48fd8
|
@ -50,6 +50,12 @@ static void calc_XY_velocity(){
|
|||
// y_GPS_speed positve = Up
|
||||
// x_GPS_speed positve = Right
|
||||
|
||||
// initialise last_longitude and last_latitude
|
||||
if( last_longitude == 0 && last_latitude == 0 ) {
|
||||
last_longitude = g_gps->longitude;
|
||||
last_latitude = g_gps->latitude;
|
||||
}
|
||||
|
||||
// this speed is ~ in cm because we are using 10^7 numbers from GPS
|
||||
float tmp = 1.0/dTnav;
|
||||
|
||||
|
|
Loading…
Reference in New Issue