mirror of https://github.com/ArduPilot/ardupilot
Rover: remove dead gcs failsafe code
Also use rc().has_valid_input() before using radio for trim
This commit is contained in:
parent
66525ab0f9
commit
5d923aed85
|
@ -780,8 +780,6 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
|||
RC_Channels::set_override(6, packet.chan7_raw, tnow);
|
||||
RC_Channels::set_override(7, packet.chan8_raw, tnow);
|
||||
|
||||
rover.failsafe.rc_override_timer = tnow;
|
||||
rover.failsafe_trigger(FAILSAFE_EVENT_RC, false);
|
||||
break;
|
||||
}
|
||||
|
||||
|
@ -805,8 +803,6 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
|||
RC_Channels::set_override(uint8_t(rover.rcmap.roll() - 1), roll, tnow);
|
||||
RC_Channels::set_override(uint8_t(rover.rcmap.throttle() - 1), throttle, tnow);
|
||||
|
||||
rover.failsafe.rc_override_timer = tnow;
|
||||
rover.failsafe_trigger(FAILSAFE_EVENT_RC, false);
|
||||
break;
|
||||
}
|
||||
|
||||
|
@ -817,7 +813,7 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
|||
break;
|
||||
}
|
||||
|
||||
rover.last_heartbeat_ms = rover.failsafe.rc_override_timer = AP_HAL::millis();
|
||||
rover.last_heartbeat_ms = AP_HAL::millis();
|
||||
rover.failsafe_trigger(FAILSAFE_EVENT_GCS, false);
|
||||
break;
|
||||
}
|
||||
|
|
|
@ -100,9 +100,6 @@ bool RC_Channels_Rover::has_valid_input() const
|
|||
if (rover.failsafe.bits & FAILSAFE_EVENT_THROTTLE) {
|
||||
return false;
|
||||
}
|
||||
if (rover.failsafe.bits & FAILSAFE_EVENT_RC) {
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
|
|
|
@ -26,13 +26,13 @@ private:
|
|||
|
||||
class RC_Channels_Rover : public RC_Channels
|
||||
{
|
||||
bool has_valid_input() const override;
|
||||
|
||||
int8_t flight_mode_channel_number() const override;
|
||||
|
||||
public:
|
||||
|
||||
bool has_valid_input() const override;
|
||||
|
||||
RC_Channel_Rover obj_channels[NUM_RC_CHANNELS];
|
||||
|
||||
RC_Channel_Rover *channel(const uint8_t chan) override {
|
||||
if (chan > NUM_RC_CHANNELS) {
|
||||
return nullptr;
|
||||
|
@ -40,4 +40,7 @@ public:
|
|||
return &obj_channels[chan];
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
int8_t flight_mode_channel_number() const override;
|
||||
};
|
||||
|
|
|
@ -247,16 +247,12 @@ private:
|
|||
// This is set to -1 when we need to re-read the switch
|
||||
uint8_t oldSwitchPosition;
|
||||
|
||||
// A flag if GCS joystick control is in use
|
||||
bool rc_override_active;
|
||||
|
||||
// Failsafe
|
||||
// A tracking variable for type of failsafe active
|
||||
// Used for failsafe based on loss of RC signal or GCS signal. See
|
||||
// FAILSAFE_EVENT_*
|
||||
struct {
|
||||
uint8_t bits;
|
||||
uint32_t rc_override_timer;
|
||||
uint32_t start_time;
|
||||
uint8_t triggered;
|
||||
uint32_t last_valid_rc_ms;
|
||||
|
|
|
@ -20,7 +20,6 @@
|
|||
// types of failsafe events
|
||||
#define FAILSAFE_EVENT_THROTTLE (1<<0)
|
||||
#define FAILSAFE_EVENT_GCS (1<<1)
|
||||
#define FAILSAFE_EVENT_RC (1<<2)
|
||||
|
||||
// Logging parameters
|
||||
#define LOG_THR_MSG 0x01
|
||||
|
|
|
@ -124,21 +124,16 @@ void Rover::control_failsafe(uint16_t pwm)
|
|||
return;
|
||||
}
|
||||
|
||||
// Check for failsafe condition based on loss of GCS control
|
||||
if (rc_override_active) {
|
||||
failsafe_trigger(FAILSAFE_EVENT_RC, (millis() - failsafe.rc_override_timer) > 1500);
|
||||
} else if (g.fs_throttle_enabled) {
|
||||
bool failed = pwm < static_cast<uint16_t>(g.fs_throttle_value);
|
||||
if (AP_HAL::millis() - failsafe.last_valid_rc_ms > 2000) {
|
||||
failed = true;
|
||||
}
|
||||
failsafe_trigger(FAILSAFE_EVENT_THROTTLE, failed);
|
||||
bool failed = pwm < static_cast<uint16_t>(g.fs_throttle_value);
|
||||
if (AP_HAL::millis() - failsafe.last_valid_rc_ms > 2000) {
|
||||
failed = true;
|
||||
}
|
||||
failsafe_trigger(FAILSAFE_EVENT_THROTTLE, failed);
|
||||
}
|
||||
|
||||
bool Rover::trim_radio()
|
||||
{
|
||||
if (failsafe.bits & FAILSAFE_EVENT_RC) {
|
||||
if (!rc().has_valid_input()) {
|
||||
// can't trim without valid input
|
||||
return false;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue