mirror of https://github.com/ArduPilot/ardupilot
Copter: Use AHRS heading in GLOBAL_POSITION_INT message
The definition of the heading field for GLOBAL_POSITION_INT is the compass heading, and so it is used for Plane and Rover. Copter however uses the GPS course over ground in this field. My personal beef with this is simply that the mapping display in MAVProxy is wrong for Copter. The question is: Do any GCS currently rely on this field for GPS course rather than getting it from GPS_RAW_INT as they should?
This commit is contained in:
parent
e54bf3e87c
commit
58735ac1aa
|
@ -249,7 +249,7 @@ static void NOINLINE send_location(mavlink_channel_t chan)
|
|||
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)
|
||||
g_gps->ground_course_cd); // course in 1/100 degree
|
||||
ahrs.yaw_sensor); // compass heading in 1/100 degree
|
||||
}
|
||||
|
||||
static void NOINLINE send_nav_controller_output(mavlink_channel_t chan)
|
||||
|
|
Loading…
Reference in New Issue