@ -1553,3 +1553,13 @@ bool GCS_MAVLINK_Copter::set_mode(const uint8_t mode)
#endif
return copter.set_mode((control_mode_t)mode, MODE_REASON_GCS_COMMAND);
}
float GCS_MAVLINK_Copter::vfr_hud_alt() const
{
if (copter.g2.dev_options.get() & DevOptionVFR_HUDRelativeAlt) {
// compatability option for older mavlink-aware devices that
// assume Copter returns a relative altitude in VFR_HUD.alt
return copter.current_loc.alt / 100.0f;
return GCS_MAVLINK::vfr_hud_alt();
@ -58,6 +58,8 @@ private:
MAV_STATE system_status() const override;
int16_t vfr_hud_throttle() const override;
float vfr_hud_alt() const override;
void send_pid_tuning();
};
@ -814,7 +814,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @Param: DEV_OPTIONS
// @DisplayName: Development options
// @Description: Bitmask of developer options. The meanings of the bit fields in this parameter may vary at any time. Developers should check the source code for current meaning
// @Bitmask: 0:ADSBMavlinkProcessing
// @Bitmask: 0:ADSBMavlinkProcessing,1:DevOptionVFR_HUDRelativeAlt
// @User: Advanced
AP_GROUPINFO("DEV_OPTIONS", 7, ParametersG2, dev_options, 0),
@ -232,6 +232,7 @@ enum PayloadPlaceStateType {
// bit options for DEV_OPTIONS parameter
enum DevOptions {
DevOptionADSBMAVLink = 1,
DevOptionVFR_HUDRelativeAlt = 2,
// Logging parameters