RC_Channel: remove min-max-configured pre-arm checks

These are really, really expensive to run while your RC isn't
configured.

We now have a split between inputs (RC) and servos (SRV), so these
aren't as critical as they were.  We also have range checks to ensure
they're roughly good enough to fly with.
This commit is contained in:
Peter Barker 2018-08-04 17:06:21 +10:00 committed by Andrew Tridgell
parent eaefdcfac2
commit e4ff937c96
2 changed files with 1 additions and 22 deletions

View File

@ -29,8 +29,6 @@ extern const AP_HAL::HAL& hal;
#include <GCS_MAVLink/GCS.h> #include <GCS_MAVLink/GCS.h>
uint32_t RC_Channel::configured_mask;
const AP_Param::GroupInfo RC_Channel::var_info[] = { const AP_Param::GroupInfo RC_Channel::var_info[] = {
// @Param: MIN // @Param: MIN
// @DisplayName: RC min PWM // @DisplayName: RC min PWM
@ -340,20 +338,6 @@ bool RC_Channel::has_override() const
((AP_HAL::millis() - last_override_time) < (uint32_t)(override_timeout * 1000))); ((AP_HAL::millis() - last_override_time) < (uint32_t)(override_timeout * 1000)));
} }
bool RC_Channel::min_max_configured() const
{
if (configured_mask & (1U << ch_in)) {
return true;
}
if (radio_min.configured() && radio_max.configured()) {
// once a channel is known to be configured it has to stay
// configured due to the nature of AP_Param
configured_mask |= (1U<<ch_in);
return true;
}
return false;
}
// //
// support for auxillary switches: // support for auxillary switches:
// //

View File

@ -97,9 +97,7 @@ public:
// set and save trim if changed // set and save trim if changed
void set_and_save_radio_trim(int16_t val) { radio_trim.set_and_save_ifchanged(val);} void set_and_save_radio_trim(int16_t val) { radio_trim.set_and_save_ifchanged(val);}
bool min_max_configured() const;
AP_Int16 option; // e.g. activate EPM gripper / enable fence AP_Int16 option; // e.g. activate EPM gripper / enable fence
// auxillary switch support: // auxillary switch support:
@ -215,9 +213,6 @@ private:
uint16_t override_value; uint16_t override_value;
uint32_t last_override_time; uint32_t last_override_time;
// bits set when channel has been identified as configured
static uint32_t configured_mask;
int16_t pwm_to_angle(); int16_t pwm_to_angle();
int16_t pwm_to_angle_dz(uint16_t dead_zone); int16_t pwm_to_angle_dz(uint16_t dead_zone);