Sub: move try_send_message send_hwstatus up
This commit is contained in:
parent
089f6f4650
commit
7c5ed54ffc
@ -293,14 +293,6 @@ void NOINLINE Sub::send_simstate(mavlink_channel_t chan)
|
||||
#endif
|
||||
}
|
||||
|
||||
void NOINLINE Sub::send_hwstatus(mavlink_channel_t chan)
|
||||
{
|
||||
mavlink_msg_hwstatus_send(
|
||||
chan,
|
||||
hal.analogin->board_voltage()*1000,
|
||||
0);
|
||||
}
|
||||
|
||||
void NOINLINE Sub::send_radio_out(mavlink_channel_t chan)
|
||||
{
|
||||
mavlink_msg_servo_output_raw_send(
|
||||
@ -585,11 +577,6 @@ bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id)
|
||||
send_ahrs2(sub.ahrs);
|
||||
break;
|
||||
|
||||
case MSG_HWSTATUS:
|
||||
CHECK_PAYLOAD_SIZE(HWSTATUS);
|
||||
sub.send_hwstatus(chan);
|
||||
break;
|
||||
|
||||
case MSG_MOUNT_STATUS:
|
||||
#if MOUNT == ENABLED
|
||||
CHECK_PAYLOAD_SIZE(MOUNT_STATUS);
|
||||
|
@ -483,7 +483,6 @@ private:
|
||||
void send_location(mavlink_channel_t chan);
|
||||
void send_nav_controller_output(mavlink_channel_t chan);
|
||||
void send_simstate(mavlink_channel_t chan);
|
||||
void send_hwstatus(mavlink_channel_t chan);
|
||||
void send_radio_out(mavlink_channel_t chan);
|
||||
void send_vfr_hud(mavlink_channel_t chan);
|
||||
#if RPM_ENABLED == ENABLED
|
||||
|
Loading…
Reference in New Issue
Block a user