Browse Source

Copter: send LOCAL_POSITION_NED

very useful for GPS-disabled operation and EKF debugging
master
Andrew Tridgell 10 years ago
parent
commit
29be2f0b60
  1. 6
      ArduCopter/GCS_Mavlink.pde

6
ArduCopter/GCS_Mavlink.pde

@ -487,6 +487,11 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id) @@ -487,6 +487,11 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
send_location(chan);
break;
case MSG_LOCAL_POSITION:
CHECK_PAYLOAD_SIZE(LOCAL_POSITION_NED);
send_local_position(ahrs);
break;
case MSG_NAV_CONTROLLER_OUTPUT:
CHECK_PAYLOAD_SIZE(NAV_CONTROLLER_OUTPUT);
send_nav_controller_output(chan);
@ -819,6 +824,7 @@ GCS_MAVLINK::data_stream_send(void) @@ -819,6 +824,7 @@ GCS_MAVLINK::data_stream_send(void)
if (stream_trigger(STREAM_POSITION)) {
send_message(MSG_LOCATION);
send_message(MSG_LOCAL_POSITION);
}
if (gcs_out_of_time) return;

Loading…
Cancel
Save