Rover: move sending of vfr_hud up

This commit is contained in:
Peter Barker 2018-01-31 13:11:27 +11:00 committed by Andrew Tridgell
parent 8b4ffb11f5
commit 9d83ee8cc7
3 changed files with 5 additions and 15 deletions

View File

@ -140,16 +140,9 @@ void Rover::send_servo_out(mavlink_channel_t chan)
rssi.read_receiver_rssi_uint8());
}
void Rover::send_vfr_hud(mavlink_channel_t chan)
int16_t GCS_MAVLINK_Rover::vfr_hud_throttle() const
{
mavlink_msg_vfr_hud_send(
chan,
gps.ground_speed(),
ahrs.groundspeed(),
(ahrs.yaw_sensor / 100) % 360,
g2.motors.get_throttle(),
current_loc.alt / 100.0f,
0);
return rover.g2.motors.get_throttle();
}
void Rover::send_rangefinder(mavlink_channel_t chan)
@ -284,11 +277,6 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
rover.send_servo_out(chan);
break;
case MSG_VFR_HUD:
CHECK_PAYLOAD_SIZE(VFR_HUD);
rover.send_vfr_hud(chan);
break;
case MSG_RANGEFINDER:
CHECK_PAYLOAD_SIZE(RANGEFINDER);
rover.send_rangefinder(chan);

View File

@ -41,4 +41,7 @@ private:
MAV_MODE base_mode() const override;
uint32_t custom_mode() const override;
MAV_STATE system_status() const override;
int16_t vfr_hud_throttle() const override;
};

View File

@ -465,7 +465,6 @@ private:
void send_extended_status1(mavlink_channel_t chan);
void send_nav_controller_output(mavlink_channel_t chan);
void send_servo_out(mavlink_channel_t chan);
void send_vfr_hud(mavlink_channel_t chan);
void send_rangefinder(mavlink_channel_t chan);
void send_pid_tuning(mavlink_channel_t chan);
void send_wheel_encoder(mavlink_channel_t chan);