mirror of https://github.com/ArduPilot/ardupilot
APM: report the nav_bearing as hold_course when enabled
this gives a more accurate view of the navigation code, as when hold_course is not -1 it overrides nav_bearing
This commit is contained in:
parent
252a2d0c9b
commit
c6b6320b43
|
@ -322,12 +322,13 @@ static void NOINLINE send_location(mavlink_channel_t chan)
|
||||||
|
|
||||||
static void NOINLINE send_nav_controller_output(mavlink_channel_t chan)
|
static void NOINLINE send_nav_controller_output(mavlink_channel_t chan)
|
||||||
{
|
{
|
||||||
|
int16_t bearing = (hold_course==-1?nav_bearing:hold_course) / 100;
|
||||||
mavlink_msg_nav_controller_output_send(
|
mavlink_msg_nav_controller_output_send(
|
||||||
chan,
|
chan,
|
||||||
nav_roll / 1.0e2,
|
nav_roll / 1.0e2,
|
||||||
nav_pitch / 1.0e2,
|
nav_pitch / 1.0e2,
|
||||||
nav_bearing / 1.0e2,
|
bearing,
|
||||||
target_bearing / 1.0e2,
|
target_bearing / 100,
|
||||||
wp_distance,
|
wp_distance,
|
||||||
altitude_error / 1.0e2,
|
altitude_error / 1.0e2,
|
||||||
airspeed_error,
|
airspeed_error,
|
||||||
|
|
Loading…
Reference in New Issue