mirror of https://github.com/ArduPilot/ardupilot
Rover: rename system_status as it won't be called from base class
This commit is contained in:
parent
314ea32ede
commit
eb330b60ed
|
@ -58,7 +58,7 @@ uint32_t GCS_Rover::custom_mode() const
|
||||||
return rover.control_mode->mode_number();
|
return rover.control_mode->mode_number();
|
||||||
}
|
}
|
||||||
|
|
||||||
MAV_STATE GCS_MAVLINK_Rover::system_status() const
|
MAV_STATE GCS_MAVLINK_Rover::vehicle_system_status() const
|
||||||
{
|
{
|
||||||
if ((rover.failsafe.triggered != 0) || rover.failsafe.ekf) {
|
if ((rover.failsafe.triggered != 0) || rover.failsafe.ekf) {
|
||||||
return MAV_STATE_CRITICAL;
|
return MAV_STATE_CRITICAL;
|
||||||
|
|
|
@ -43,7 +43,7 @@ private:
|
||||||
void packetReceived(const mavlink_status_t &status, const mavlink_message_t &msg) override;
|
void packetReceived(const mavlink_status_t &status, 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;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue