mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
AP_Arming: remove unused parameter and variable
This commit is contained in:
parent
0800f72377
commit
dd2798d099
@ -745,7 +745,7 @@ AP_Arming::ArmingRequired AP_Arming::arming_required()
|
||||
|
||||
// Copter and sub share the same RC input limits
|
||||
// Copter checks that min and max have been configured by default, Sub does not
|
||||
bool AP_Arming::rc_checks_copter_sub(const bool display_failure, const RC_Channel *channels[4], const bool check_min_max) const
|
||||
bool AP_Arming::rc_checks_copter_sub(const bool display_failure, const RC_Channel *channels[4]) const
|
||||
{
|
||||
// set rc-checks to success if RC checks are disabled
|
||||
if ((checks_to_perform != ARMING_CHECK_ALL) && !(checks_to_perform & ARMING_CHECK_RC)) {
|
||||
|
@ -87,7 +87,6 @@ protected:
|
||||
|
||||
// internal members
|
||||
bool armed:1;
|
||||
bool logging_available:1;
|
||||
uint32_t last_accel_pass_ms[INS_MAX_INSTANCES];
|
||||
uint32_t last_gyro_pass_ms[INS_MAX_INSTANCES];
|
||||
|
||||
@ -118,7 +117,7 @@ protected:
|
||||
virtual bool system_checks(bool report);
|
||||
|
||||
bool servo_checks(bool report) const;
|
||||
bool rc_checks_copter_sub(bool display_failure, const RC_Channel *channels[4], const bool check_min_max = true) const;
|
||||
bool rc_checks_copter_sub(bool display_failure, const RC_Channel *channels[4]) const;
|
||||
|
||||
// returns true if a particular check is enabled
|
||||
bool check_enabled(const enum AP_Arming::ArmingChecks check) const;
|
||||
|
Loading…
Reference in New Issue
Block a user