mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
RC_Channel: improved efficiency of min_max_configured
this is quite a costly function due to scan in AP_Param. It takes about 4 to 5 milliseconds when done as part of AP_Arming
This commit is contained in:
parent
746ca91649
commit
e5813effff
@ -27,6 +27,8 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
#include "RC_Channel.h"
|
||||
|
||||
uint32_t RC_Channel::configured_mask;
|
||||
|
||||
const AP_Param::GroupInfo RC_Channel::var_info[] = {
|
||||
// @Param: MIN
|
||||
// @DisplayName: RC min PWM
|
||||
@ -335,3 +337,17 @@ bool RC_Channel::in_trim_dz()
|
||||
return is_bounded_int32(radio_in, radio_trim - dead_zone, radio_trim + dead_zone);
|
||||
}
|
||||
|
||||
|
||||
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;
|
||||
}
|
||||
|
@ -97,10 +97,7 @@ public:
|
||||
|
||||
void set_and_save_trim() { radio_trim.set_and_save_ifchanged(radio_in);}
|
||||
|
||||
bool min_max_configured() const
|
||||
{
|
||||
return radio_min.configured() && radio_max.configured();
|
||||
}
|
||||
bool min_max_configured() const;
|
||||
|
||||
private:
|
||||
|
||||
@ -123,6 +120,9 @@ private:
|
||||
// the input channel this corresponds to
|
||||
uint8_t ch_in;
|
||||
|
||||
// bits set when channel has been identified as configured
|
||||
static uint32_t configured_mask;
|
||||
|
||||
int16_t pwm_to_angle();
|
||||
int16_t pwm_to_angle_dz(uint16_t dead_zone);
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user