Browse Source

Plane: Send BATTERY_STATUS

master
Michael du Breuil 8 years ago committed by Randy Mackay
parent
commit
b850c1041f
  1. 4
      ArduPlane/GCS_Mavlink.cpp

4
ArduPlane/GCS_Mavlink.cpp

@ -684,6 +684,9 @@ bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id) @@ -684,6 +684,9 @@ bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id)
CHECK_PAYLOAD_SIZE(ADSB_VEHICLE);
plane.adsb.send_adsb_vehicle(chan);
break;
case MSG_BATTERY_STATUS:
send_battery_status(plane.battery);
break;
}
return true;
}
@ -895,6 +898,7 @@ GCS_MAVLINK_Plane::data_stream_send(void) @@ -895,6 +898,7 @@ GCS_MAVLINK_Plane::data_stream_send(void)
send_message(MSG_MAG_CAL_REPORT);
send_message(MSG_MAG_CAL_PROGRESS);
send_message(MSG_BATTERY2);
send_message(MSG_BATTERY_STATUS);
send_message(MSG_MOUNT_STATUS);
send_message(MSG_OPTICAL_FLOW);
send_message(MSG_EKF_STATUS_REPORT);

Loading…
Cancel
Save