Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Plane: don't trigger RC failsafe until RC has been received for the first time #23189

Merged
merged 1 commit into from
May 1, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
35 changes: 34 additions & 1 deletion ArduPlane/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ bool AP_Arming_Plane::pre_arm_checks(bool display_failure)
}
//are arming checks disabled?
if (checks_to_perform == 0) {
return true;
return mandatory_checks(display_failure);
Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

As well as the new check we gain the base class checks in this case:

bool AP_Arming::mandatory_checks(bool report)
{
bool ret = true;
#if AP_OPENDRONEID_ENABLED
ret &= opendroneid_checks(report);
#endif
ret &= rc_in_calibration_check(report);
ret &= serial_protocol_checks(report);
return ret;
}

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

wont this prevent RC less operation? never advised but was not prohibited before....

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

No, you just have to turn off the RC failsafe.

}
if (hal.util->was_watchdog_armed()) {
// on watchdog reset bypass arming checks to allow for
Expand Down Expand Up @@ -91,6 +91,8 @@ bool AP_Arming_Plane::pre_arm_checks(bool display_failure)
ret = false;
}

ret &= rc_received_if_enabled_check(display_failure);

#if HAL_QUADPLANE_ENABLED
ret &= quadplane_checks(display_failure);
#endif
Expand Down Expand Up @@ -124,6 +126,19 @@ bool AP_Arming_Plane::pre_arm_checks(bool display_failure)
return ret;
}

bool AP_Arming_Plane::mandatory_checks(bool display_failure)
{
bool ret = true;

ret &= rc_received_if_enabled_check(display_failure);

// Call parent class checks
ret &= AP_Arming::mandatory_checks(display_failure);

return ret;
}


#if HAL_QUADPLANE_ENABLED
bool AP_Arming_Plane::quadplane_checks(bool display_failure)
{
Expand Down Expand Up @@ -411,3 +426,21 @@ bool AP_Arming_Plane::mission_checks(bool report)
#endif
return ret;
}

// Checks rc has been received if it is configured to be used
bool AP_Arming_Plane::rc_received_if_enabled_check(bool display_failure)
{
if (rc().enabled_protocols() == 0) {
// No protocols enabled, will never get RC, don't block arming
return true;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this is badly named function if it returns true for "rc_received_check()" when there is no RC

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Changed to rc_received_if_enabled_check

}

// If RC failsafe is enabled we must receive RC before arming
if ((Plane::ThrFailsafe(plane.g.throttle_fs_enabled.get()) == Plane::ThrFailsafe::Enabled) &&
!(rc().has_had_rc_receiver() || rc().has_had_rc_override())) {
check_failed(display_failure, "Waiting for RC");
return false;
}

return true;
}
6 changes: 6 additions & 0 deletions ArduPlane/AP_Arming.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,13 +29,19 @@ class AP_Arming_Plane : public AP_Arming
void update_soft_armed();
bool get_delay_arming() const { return delay_arming; };

// mandatory checks that cannot be bypassed. This function will only be called if ARMING_CHECK is zero or arming forced
bool mandatory_checks(bool display_failure) override;

protected:
bool ins_checks(bool report) override;
bool terrain_database_required() const override;

bool quadplane_checks(bool display_failure);
bool mission_checks(bool report) override;

// Checks rc has been received if it is configured to be used
bool rc_received_if_enabled_check(bool display_failure);

private:
void change_arm_state(void);

Expand Down
5 changes: 4 additions & 1 deletion ArduPlane/radio.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -278,7 +278,10 @@ void Plane::control_failsafe()
}
}

if (ThrFailsafe(g.throttle_fs_enabled.get()) != ThrFailsafe::Enabled) {
const bool allow_failsafe_bypass = !arming.is_armed() && !is_flying() && (rc().enabled_protocols() != 0);
const bool has_had_input = rc().has_had_rc_receiver() || rc().has_had_rc_override();
if ((ThrFailsafe(g.throttle_fs_enabled.get()) != ThrFailsafe::Enabled) || (allow_failsafe_bypass && !has_had_input)) {
// If not flying and disarmed don't trigger failsafe until RC has been received for the fist time
return;
}

Expand Down