mirror of https://github.com/ArduPilot/ardupilot
Copter: rename system_status as it won't be called from base class
This commit is contained in:
parent
f291013268
commit
ad2c9d4e7e
|
@ -72,7 +72,7 @@ uint32_t GCS_Copter::custom_mode() const
|
||||||
return (uint32_t)copter.control_mode;
|
return (uint32_t)copter.control_mode;
|
||||||
}
|
}
|
||||||
|
|
||||||
MAV_STATE GCS_MAVLINK_Copter::system_status() const
|
MAV_STATE GCS_MAVLINK_Copter::vehicle_system_status() const
|
||||||
{
|
{
|
||||||
// set system as critical if any failsafe have triggered
|
// set system as critical if any failsafe have triggered
|
||||||
if (copter.any_failsafe_triggered()) {
|
if (copter.any_failsafe_triggered()) {
|
||||||
|
|
|
@ -57,7 +57,7 @@ private:
|
||||||
const mavlink_message_t &msg) override;
|
const mavlink_message_t &msg) override;
|
||||||
|
|
||||||
MAV_MODE base_mode() const override;
|
MAV_MODE base_mode() const override;
|
||||||
MAV_STATE system_status() const override;
|
MAV_STATE vehicle_system_status() const override;
|
||||||
|
|
||||||
int16_t vfr_hud_throttle() const override;
|
int16_t vfr_hud_throttle() const override;
|
||||||
float vfr_hud_alt() const override;
|
float vfr_hud_alt() const override;
|
||||||
|
|
Loading…
Reference in New Issue