GCS_MAVLink: move try_send_message send_hwstatus up

This commit is contained in:
Peter Barker 2017-07-18 21:50:23 +10:00 committed by Francisco Ferreira
parent 4da89a948a
commit 679bb7f7a5
2 changed files with 14 additions and 0 deletions

View File

@ -290,6 +290,7 @@ protected:
// message sending functions:
bool try_send_compass_message(enum ap_message id);
bool try_send_mission_message(enum ap_message id);
void send_hwstatus();
private:

View File

@ -2085,6 +2085,13 @@ bool GCS_MAVLINK::try_send_mission_message(const enum ap_message id)
return ret;
}
void GCS_MAVLINK::send_hwstatus()
{
mavlink_msg_hwstatus_send(
chan,
hal.analogin->board_voltage()*1000,
0);
}
bool GCS_MAVLINK::try_send_message(const enum ap_message id)
{
@ -2096,6 +2103,12 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
switch(id) {
case MSG_HWSTATUS:
CHECK_PAYLOAD_SIZE(HWSTATUS);
send_hwstatus();
ret = true;
break;
case MSG_CURRENT_WAYPOINT:
/* fall through */
case MSG_MISSION_ITEM_REACHED: