mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
APM: use raw GPS velocity in GLOBAL_POSITION_INT
a much more useful value to log
This commit is contained in:
parent
ea40432235
commit
2793e432ff
@ -238,9 +238,9 @@ static void NOINLINE send_location(mavlink_channel_t chan)
|
||||
current_loc.lng, // in 1E7 degrees
|
||||
g_gps->altitude * 10, // millimeters above sea level
|
||||
(current_loc.alt-home.alt) * 10, // millimeters above ground
|
||||
g_gps->ground_speed * rot.a.x, // X speed cm/s
|
||||
g_gps->ground_speed * rot.b.x, // Y speed cm/s
|
||||
g_gps->ground_speed * rot.c.x,
|
||||
g_gps->velocity_north() * 100, // X speed cm/s (+ve North)
|
||||
g_gps->velocity_east() * 100, // Y speed cm/s (+ve East)
|
||||
g_gps->velocity_down() * -100, // Z speed cm/s (+ve up)
|
||||
ahrs.yaw_sensor);
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user