mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
Rover: move try_send_message send_hwstatus up
This commit is contained in:
parent
e08b87763e
commit
dbac7447d6
@ -182,14 +182,6 @@ void Rover::send_simstate(mavlink_channel_t chan)
|
||||
#endif
|
||||
}
|
||||
|
||||
void Rover::send_hwstatus(mavlink_channel_t chan)
|
||||
{
|
||||
mavlink_msg_hwstatus_send(
|
||||
chan,
|
||||
hal.analogin->board_voltage() * 1000,
|
||||
0);
|
||||
}
|
||||
|
||||
void Rover::send_rangefinder(mavlink_channel_t chan)
|
||||
{
|
||||
if (!rangefinder.has_data(0) && !rangefinder.has_data(1)) {
|
||||
@ -397,11 +389,6 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
|
||||
rover.send_simstate(chan);
|
||||
break;
|
||||
|
||||
case MSG_HWSTATUS:
|
||||
CHECK_PAYLOAD_SIZE(HWSTATUS);
|
||||
rover.send_hwstatus(chan);
|
||||
break;
|
||||
|
||||
case MSG_RANGEFINDER:
|
||||
CHECK_PAYLOAD_SIZE(RANGEFINDER);
|
||||
rover.send_rangefinder(chan);
|
||||
|
@ -458,7 +458,6 @@ private:
|
||||
void send_servo_out(mavlink_channel_t chan);
|
||||
void send_vfr_hud(mavlink_channel_t chan);
|
||||
void send_simstate(mavlink_channel_t chan);
|
||||
void send_hwstatus(mavlink_channel_t chan);
|
||||
void send_pid_tuning(mavlink_channel_t chan);
|
||||
void send_rangefinder(mavlink_channel_t chan);
|
||||
void send_wheel_encoder(mavlink_channel_t chan);
|
||||
|
Loading…
Reference in New Issue
Block a user