mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 02:33:58 -04:00
AP_Arming: add reset_all_aux_auths
This commit is contained in:
parent
71be1194cb
commit
7b3a6434de
@ -1464,6 +1464,27 @@ void AP_Arming::set_aux_auth_failed(uint8_t auth_id, const char* fail_msg)
|
||||
}
|
||||
}
|
||||
|
||||
void AP_Arming::reset_all_aux_auths()
|
||||
{
|
||||
WITH_SEMAPHORE(aux_auth_sem);
|
||||
|
||||
// clear all auxiliary authorisation ids
|
||||
aux_auth_count = 0;
|
||||
// clear any previous allocation errors
|
||||
aux_auth_error = false;
|
||||
|
||||
// reset states for all auxiliary authorisation ids
|
||||
for (uint8_t i = 0; i < aux_auth_count_max; i++) {
|
||||
aux_auth_state[i] = AuxAuthStates::NO_RESPONSE;
|
||||
}
|
||||
|
||||
// free up the failure message buffer
|
||||
if (aux_auth_fail_msg != nullptr) {
|
||||
free(aux_auth_fail_msg);
|
||||
aux_auth_fail_msg = nullptr;
|
||||
}
|
||||
}
|
||||
|
||||
bool AP_Arming::aux_auth_checks(bool display_failure)
|
||||
{
|
||||
// handle error cases
|
||||
|
@ -129,6 +129,7 @@ public:
|
||||
bool get_aux_auth_id(uint8_t& auth_id);
|
||||
void set_aux_auth_passed(uint8_t auth_id);
|
||||
void set_aux_auth_failed(uint8_t auth_id, const char* fail_msg);
|
||||
void reset_all_aux_auths();
|
||||
#endif
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
Loading…
Reference in New Issue
Block a user