|
|
@ -101,14 +101,6 @@ void Tracker::send_location(mavlink_channel_t chan) |
|
|
|
ahrs.yaw_sensor); |
|
|
|
ahrs.yaw_sensor); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
void Tracker::send_hwstatus(mavlink_channel_t chan) |
|
|
|
|
|
|
|
{ |
|
|
|
|
|
|
|
mavlink_msg_hwstatus_send( |
|
|
|
|
|
|
|
chan, |
|
|
|
|
|
|
|
0, |
|
|
|
|
|
|
|
0); |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
void Tracker::send_nav_controller_output(mavlink_channel_t chan) |
|
|
|
void Tracker::send_nav_controller_output(mavlink_channel_t chan) |
|
|
|
{ |
|
|
|
{ |
|
|
|
float alt_diff = (g.alt_source == ALT_SOURCE_BARO) ? nav_status.alt_difference_baro : nav_status.alt_difference_gps; |
|
|
|
float alt_diff = (g.alt_source == ALT_SOURCE_BARO) ? nav_status.alt_difference_baro : nav_status.alt_difference_gps; |
|
|
@ -220,11 +212,6 @@ bool GCS_MAVLINK_Tracker::try_send_message(enum ap_message id) |
|
|
|
tracker.send_simstate(chan); |
|
|
|
tracker.send_simstate(chan); |
|
|
|
break; |
|
|
|
break; |
|
|
|
|
|
|
|
|
|
|
|
case MSG_HWSTATUS: |
|
|
|
|
|
|
|
CHECK_PAYLOAD_SIZE(HWSTATUS); |
|
|
|
|
|
|
|
tracker.send_hwstatus(chan); |
|
|
|
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
default: |
|
|
|
default: |
|
|
|
return GCS_MAVLINK::try_send_message(id); |
|
|
|
return GCS_MAVLINK::try_send_message(id); |
|
|
|
} |
|
|
|
} |
|
|
|