mirror of https://github.com/ArduPilot/ardupilot
Sub: move sending of vfr_hud up
This commit is contained in:
parent
9d83ee8cc7
commit
18c494b25f
|
@ -251,16 +251,9 @@ void NOINLINE Sub::send_nav_controller_output(mavlink_channel_t chan)
|
||||||
0);
|
0);
|
||||||
}
|
}
|
||||||
|
|
||||||
void NOINLINE Sub::send_vfr_hud(mavlink_channel_t chan)
|
int16_t GCS_MAVLINK_Sub::vfr_hud_throttle() const
|
||||||
{
|
{
|
||||||
mavlink_msg_vfr_hud_send(
|
return (int16_t)(sub.motors.get_throttle() * 100);
|
||||||
chan,
|
|
||||||
gps.ground_speed(),
|
|
||||||
gps.ground_speed(),
|
|
||||||
(ahrs.yaw_sensor / 100) % 360,
|
|
||||||
(int16_t)(motors.get_throttle() * 100),
|
|
||||||
current_loc.alt / 100.0f,
|
|
||||||
climb_rate / 100.0f);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -427,11 +420,6 @@ bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id)
|
||||||
sub.send_nav_controller_output(chan);
|
sub.send_nav_controller_output(chan);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSG_VFR_HUD:
|
|
||||||
CHECK_PAYLOAD_SIZE(VFR_HUD);
|
|
||||||
sub.send_vfr_hud(chan);
|
|
||||||
break;
|
|
||||||
|
|
||||||
case MSG_RPM:
|
case MSG_RPM:
|
||||||
#if RPM_ENABLED == ENABLED
|
#if RPM_ENABLED == ENABLED
|
||||||
CHECK_PAYLOAD_SIZE(RPM);
|
CHECK_PAYLOAD_SIZE(RPM);
|
||||||
|
|
|
@ -46,4 +46,8 @@ private:
|
||||||
MAV_MODE base_mode() const override;
|
MAV_MODE base_mode() const override;
|
||||||
uint32_t custom_mode() const override;
|
uint32_t custom_mode() const override;
|
||||||
MAV_STATE system_status() const override;
|
MAV_STATE system_status() const override;
|
||||||
|
|
||||||
|
int16_t vfr_hud_throttle() const override;
|
||||||
|
bool vfr_hud_make_alt_relative() const override { return true; }
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
|
@ -476,7 +476,6 @@ private:
|
||||||
void send_heartbeat(mavlink_channel_t chan);
|
void send_heartbeat(mavlink_channel_t chan);
|
||||||
void send_extended_status1(mavlink_channel_t chan);
|
void send_extended_status1(mavlink_channel_t chan);
|
||||||
void send_nav_controller_output(mavlink_channel_t chan);
|
void send_nav_controller_output(mavlink_channel_t chan);
|
||||||
void send_vfr_hud(mavlink_channel_t chan);
|
|
||||||
#if RPM_ENABLED == ENABLED
|
#if RPM_ENABLED == ENABLED
|
||||||
void send_rpm(mavlink_channel_t chan);
|
void send_rpm(mavlink_channel_t chan);
|
||||||
void rpm_update();
|
void rpm_update();
|
||||||
|
|
Loading…
Reference in New Issue