mirror of https://github.com/ArduPilot/ardupilot
AP_MotorsMulticopter: fixup check_mot_pwm_params
fix _pwm_max is positive check returns true if params are valid constify method
This commit is contained in:
parent
f00bf77af7
commit
bff978570f
|
@ -483,14 +483,14 @@ int16_t AP_MotorsMulticopter::get_pwm_output_max() const
|
|||
return _throttle_radio_max;
|
||||
}
|
||||
|
||||
// parameter checks for MOT_PWM_MIN/MAX
|
||||
bool AP_MotorsMulticopter::check_mot_pwm_params()
|
||||
// parameter checks for MOT_PWM_MIN/MAX, returns true if parameters are valid
|
||||
bool AP_MotorsMulticopter::check_mot_pwm_params() const
|
||||
{
|
||||
if ((_pwm_min == 0 && _pwm_max !=0) || (_pwm_min != 0 && _pwm_max == 0) ||
|
||||
(_pwm_min < 0 || _pwm_min < 0) || (_pwm_min > _pwm_max)) {
|
||||
return true;
|
||||
if ((_pwm_min == 0 && _pwm_max != 0) || (_pwm_min != 0 && _pwm_max == 0) ||
|
||||
(_pwm_min < 0 || _pwm_max < 0) || (_pwm_min > _pwm_max)) {
|
||||
return false;
|
||||
}
|
||||
return false;
|
||||
return true;
|
||||
}
|
||||
|
||||
// set_throttle_range - sets the minimum throttle that will be sent to the engines when they're not off (i.e. to prevents issues with some motors spinning and some not at very low throttle)
|
||||
|
|
|
@ -84,8 +84,8 @@ public:
|
|||
int16_t get_pwm_output_min() const;
|
||||
int16_t get_pwm_output_max() const;
|
||||
|
||||
// parameter check for MOT_PWM_MIN/MAX
|
||||
bool check_mot_pwm_params();
|
||||
// parameter check for MOT_PWM_MIN/MAX, returns true if parameters are valid
|
||||
bool check_mot_pwm_params() const;
|
||||
|
||||
// set thrust compensation callback
|
||||
FUNCTOR_TYPEDEF(thrust_compensation_fn_t, void, float *, uint8_t);
|
||||
|
|
Loading…
Reference in New Issue