AP_Motors: params always use set method

This commit is contained in:
Iampete1 2022-07-05 04:08:56 +01:00 committed by Peter Hall
parent 8352a7b2b3
commit c1a9f75034
10 changed files with 29 additions and 29 deletions

View File

@ -167,7 +167,7 @@ void AP_MotorsHeli::init(motor_frame_class frame_class, motor_frame_type frame_t
_servo_test_cycle_counter = _servo_test; _servo_test_cycle_counter = _servo_test;
// ensure inputs are not passed through to servos on start-up // ensure inputs are not passed through to servos on start-up
_servo_mode = SERVO_CONTROL_MODE_AUTOMATED; _servo_mode.set(SERVO_CONTROL_MODE_AUTOMATED);
// initialise radio passthrough for collective to middle // initialise radio passthrough for collective to middle
_throttle_radio_passthrough = 0.5f; _throttle_radio_passthrough = 0.5f;
@ -536,7 +536,7 @@ void AP_MotorsHeli::update_throttle_filter()
// reset_flight_controls - resets all controls and scalars to flight status // reset_flight_controls - resets all controls and scalars to flight status
void AP_MotorsHeli::reset_flight_controls() void AP_MotorsHeli::reset_flight_controls()
{ {
_servo_mode = SERVO_CONTROL_MODE_AUTOMATED; _servo_mode.set(SERVO_CONTROL_MODE_AUTOMATED);
init_outputs(); init_outputs();
calculate_scalars(); calculate_scalars();
} }
@ -564,7 +564,7 @@ void AP_MotorsHeli::update_throttle_hover(float dt)
} }
// we have chosen to constrain the hover collective to be within the range reachable by the third order expo polynomial. // we have chosen to constrain the hover collective to be within the range reachable by the third order expo polynomial.
_collective_hover = constrain_float(_collective_hover + (dt / (dt + AP_MOTORS_HELI_COLLECTIVE_HOVER_TC)) * (curr_collective - _collective_hover), AP_MOTORS_HELI_COLLECTIVE_HOVER_MIN, AP_MOTORS_HELI_COLLECTIVE_HOVER_MAX); _collective_hover.set(constrain_float(_collective_hover + (dt / (dt + AP_MOTORS_HELI_COLLECTIVE_HOVER_TC)) * (curr_collective - _collective_hover), AP_MOTORS_HELI_COLLECTIVE_HOVER_MIN, AP_MOTORS_HELI_COLLECTIVE_HOVER_MAX));
} }
} }

View File

@ -353,20 +353,20 @@ void AP_MotorsHeli_Dual::calculate_scalars()
{ {
// range check collective min, max and mid // range check collective min, max and mid
if( _collective_min >= _collective_max ) { if( _collective_min >= _collective_max ) {
_collective_min = AP_MOTORS_HELI_COLLECTIVE_MIN; _collective_min.set(AP_MOTORS_HELI_COLLECTIVE_MIN);
_collective_max = AP_MOTORS_HELI_COLLECTIVE_MAX; _collective_max.set(AP_MOTORS_HELI_COLLECTIVE_MAX);
} }
// range check collective min, max and mid for rear swashplate // range check collective min, max and mid for rear swashplate
if( _collective2_min >= _collective2_max ) { if( _collective2_min >= _collective2_max ) {
_collective2_min = AP_MOTORS_HELI_DUAL_COLLECTIVE2_MIN; _collective2_min.set(AP_MOTORS_HELI_DUAL_COLLECTIVE2_MIN);
_collective2_max = AP_MOTORS_HELI_DUAL_COLLECTIVE2_MAX; _collective2_max.set(AP_MOTORS_HELI_DUAL_COLLECTIVE2_MAX);
} }
_collective_zero_thrust_deg = constrain_float(_collective_zero_thrust_deg, _collective_min_deg, _collective_max_deg); _collective_zero_thrust_deg.set(constrain_float(_collective_zero_thrust_deg, _collective_min_deg, _collective_max_deg));
_collective_land_min_deg = constrain_float(_collective_land_min_deg, _collective_min_deg, _collective_max_deg); _collective_land_min_deg.set(constrain_float(_collective_land_min_deg, _collective_min_deg, _collective_max_deg));
if (!is_equal((float)_collective_max_deg, (float)_collective_min_deg)) { if (!is_equal((float)_collective_max_deg, (float)_collective_min_deg)) {
// calculate collective zero thrust point as a number from 0 to 1 // calculate collective zero thrust point as a number from 0 to 1

View File

@ -132,13 +132,13 @@ void AP_MotorsHeli_Quad::calculate_scalars()
{ {
// range check collective min, max and mid // range check collective min, max and mid
if( _collective_min >= _collective_max ) { if( _collective_min >= _collective_max ) {
_collective_min = AP_MOTORS_HELI_COLLECTIVE_MIN; _collective_min.set(AP_MOTORS_HELI_COLLECTIVE_MIN);
_collective_max = AP_MOTORS_HELI_COLLECTIVE_MAX; _collective_max.set(AP_MOTORS_HELI_COLLECTIVE_MAX);
} }
_collective_zero_thrust_deg = constrain_float(_collective_zero_thrust_deg, _collective_min_deg, _collective_max_deg); _collective_zero_thrust_deg.set(constrain_float(_collective_zero_thrust_deg, _collective_min_deg, _collective_max_deg));
_collective_land_min_deg = constrain_float(_collective_land_min_deg, _collective_min_deg, _collective_max_deg); _collective_land_min_deg.set(constrain_float(_collective_land_min_deg, _collective_min_deg, _collective_max_deg));
if (!is_equal((float)_collective_max_deg, (float)_collective_min_deg)) { if (!is_equal((float)_collective_max_deg, (float)_collective_min_deg)) {
// calculate collective zero thrust point as a number from 0 to 1 // calculate collective zero thrust point as a number from 0 to 1

View File

@ -72,7 +72,7 @@ public:
uint8_t get_control_mode() const { return _control_mode; } uint8_t get_control_mode() const { return _control_mode; }
// set_critical_speed // set_critical_speed
void set_critical_speed(float critical_speed) { _critical_speed = critical_speed; } void set_critical_speed(float critical_speed) { _critical_speed.set(critical_speed); }
// get_desired_speed // get_desired_speed
float get_desired_speed() const { return _desired_speed; } float get_desired_speed() const { return _desired_speed; }
@ -88,13 +88,13 @@ public:
float get_governor_output() const { return _governor_output; } float get_governor_output() const { return _governor_output; }
void governor_reset(); void governor_reset();
float get_control_output() const { return _control_output; } float get_control_output() const { return _control_output; }
void set_idle_output(float idle_output) { _idle_output = idle_output; } void set_idle_output(float idle_output) { _idle_output.set(idle_output); }
void autothrottle_run(); void autothrottle_run();
void set_throttle_curve(); void set_throttle_curve();
// functions for ramp and runup timers, runup_complete flag // functions for ramp and runup timers, runup_complete flag
void set_ramp_time(int8_t ramp_time) { _ramp_time = ramp_time; } void set_ramp_time(int8_t ramp_time) { _ramp_time.set(ramp_time); }
void set_runup_time(int8_t runup_time) { _runup_time = runup_time; } void set_runup_time(int8_t runup_time) { _runup_time.set(runup_time); }
bool is_runup_complete() const { return _runup_complete; } bool is_runup_complete() const { return _runup_complete; }
// is_spooldown_complete // is_spooldown_complete

View File

@ -310,13 +310,13 @@ void AP_MotorsHeli_Single::calculate_scalars()
{ {
// range check collective min, max and zero // range check collective min, max and zero
if( _collective_min >= _collective_max ) { if( _collective_min >= _collective_max ) {
_collective_min = AP_MOTORS_HELI_COLLECTIVE_MIN; _collective_min.set(AP_MOTORS_HELI_COLLECTIVE_MIN);
_collective_max = AP_MOTORS_HELI_COLLECTIVE_MAX; _collective_max.set(AP_MOTORS_HELI_COLLECTIVE_MAX);
} }
_collective_zero_thrust_deg = constrain_float(_collective_zero_thrust_deg, _collective_min_deg, _collective_max_deg); _collective_zero_thrust_deg.set(constrain_float(_collective_zero_thrust_deg, _collective_min_deg, _collective_max_deg));
_collective_land_min_deg = constrain_float(_collective_land_min_deg, _collective_min_deg, _collective_max_deg); _collective_land_min_deg.set(constrain_float(_collective_land_min_deg, _collective_min_deg, _collective_max_deg));
if (!is_equal((float)_collective_max_deg, (float)_collective_min_deg)) { if (!is_equal((float)_collective_max_deg, (float)_collective_min_deg)) {
// calculate collective zero thrust point as a number from 0 to 1 // calculate collective zero thrust point as a number from 0 to 1
@ -467,7 +467,7 @@ void AP_MotorsHeli_Single::move_actuators(float roll_out, float pitch_out, float
// also not required if we are using external gyro // also not required if we are using external gyro
if ((_main_rotor.get_control_output() > _main_rotor.get_idle_output()) && _tail_type != AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO_EXTGYRO) { if ((_main_rotor.get_control_output() > _main_rotor.get_idle_output()) && _tail_type != AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO_EXTGYRO) {
// sanity check collective_yaw_effect // sanity check collective_yaw_effect
_collective_yaw_effect = constrain_float(_collective_yaw_effect, -AP_MOTORS_HELI_SINGLE_COLYAW_RANGE, AP_MOTORS_HELI_SINGLE_COLYAW_RANGE); _collective_yaw_effect.set(constrain_float(_collective_yaw_effect, -AP_MOTORS_HELI_SINGLE_COLYAW_RANGE, AP_MOTORS_HELI_SINGLE_COLYAW_RANGE));
// the 4.5 scaling factor is to bring the values in line with previous releases // the 4.5 scaling factor is to bring the values in line with previous releases
yaw_offset = _collective_yaw_effect * fabsf(collective_out - _collective_zero_thrust_pct) / 4.5f; yaw_offset = _collective_yaw_effect * fabsf(collective_out - _collective_zero_thrust_pct) / 4.5f;
} }

View File

@ -82,7 +82,7 @@ public:
uint32_t get_motor_mask() override; uint32_t get_motor_mask() override;
// ext_gyro_gain - set external gyro gain in range 0 ~ 1000 // ext_gyro_gain - set external gyro gain in range 0 ~ 1000
void ext_gyro_gain(float gain) override { if (gain >= 0 && gain <= 1000) { _ext_gyro_gain_std = gain; }} void ext_gyro_gain(float gain) override { if (gain >= 0 && gain <= 1000) { _ext_gyro_gain_std.set(gain); }}
// has_flybar - returns true if we have a mechical flybar // has_flybar - returns true if we have a mechical flybar
bool has_flybar() const override { return _flybar_mode; } bool has_flybar() const override { return _flybar_mode; }

View File

@ -94,9 +94,9 @@ void AP_MotorsHeli_Swash::configure()
_collective_direction = static_cast<CollectiveDirection>(_swash_coll_dir.get()); _collective_direction = static_cast<CollectiveDirection>(_swash_coll_dir.get());
_make_servo_linear = _linear_swash_servo; _make_servo_linear = _linear_swash_servo;
if (_swash_type == SWASHPLATE_TYPE_H3) { if (_swash_type == SWASHPLATE_TYPE_H3) {
enable = 1; enable.set(1);
} else { } else {
enable = 0; enable.set(0);
} }
} }

View File

@ -383,7 +383,7 @@ void AP_MotorsMulticopter::update_lift_max_from_batt_voltage()
return; return;
} }
_batt_voltage_min = MAX(_batt_voltage_min, _batt_voltage_max * 0.6f); _batt_voltage_min.set(MAX(_batt_voltage_min, _batt_voltage_max * 0.6f));
// contrain resting voltage estimate (resting voltage is actual voltage with sag removed based on current draw and resistance) // contrain resting voltage estimate (resting voltage is actual voltage with sag removed based on current draw and resistance)
_batt_voltage_resting_estimate = constrain_float(_batt_voltage_resting_estimate, _batt_voltage_min, _batt_voltage_max); _batt_voltage_resting_estimate = constrain_float(_batt_voltage_resting_estimate, _batt_voltage_min, _batt_voltage_max);
@ -529,7 +529,7 @@ void AP_MotorsMulticopter::update_throttle_hover(float dt)
{ {
if (_throttle_hover_learn != HOVER_LEARN_DISABLED) { if (_throttle_hover_learn != HOVER_LEARN_DISABLED) {
// we have chosen to constrain the hover throttle to be within the range reachable by the third order expo polynomial. // we have chosen to constrain the hover throttle to be within the range reachable by the third order expo polynomial.
_throttle_hover = constrain_float(_throttle_hover + (dt / (dt + AP_MOTORS_THST_HOVER_TC)) * (get_throttle() - _throttle_hover), AP_MOTORS_THST_HOVER_MIN, AP_MOTORS_THST_HOVER_MAX); _throttle_hover.set(constrain_float(_throttle_hover + (dt / (dt + AP_MOTORS_THST_HOVER_TC)) * (get_throttle() - _throttle_hover), AP_MOTORS_THST_HOVER_MIN, AP_MOTORS_THST_HOVER_MAX));
} }
} }

View File

@ -42,7 +42,7 @@ public:
void output_min() override; void output_min() override;
// set_yaw_headroom - set yaw headroom (yaw is given at least this amount of pwm) // set_yaw_headroom - set yaw headroom (yaw is given at least this amount of pwm)
void set_yaw_headroom(int16_t pwm) { _yaw_headroom = pwm; } void set_yaw_headroom(int16_t pwm) { _yaw_headroom.set(pwm); }
// update_throttle_range - update throttle endpoints // update_throttle_range - update throttle endpoints
void update_throttle_range(); void update_throttle_range();

View File

@ -159,7 +159,7 @@ void AP_MotorsTri::output_armed_stabilizing()
SRV_Channels::set_angle(SRV_Channels::get_motor_function(AP_MOTORS_CH_TRI_YAW), _yaw_servo_angle_max_deg*100); SRV_Channels::set_angle(SRV_Channels::get_motor_function(AP_MOTORS_CH_TRI_YAW), _yaw_servo_angle_max_deg*100);
// sanity check YAW_SV_ANGLE parameter value to avoid divide by zero // sanity check YAW_SV_ANGLE parameter value to avoid divide by zero
_yaw_servo_angle_max_deg = constrain_float(_yaw_servo_angle_max_deg, AP_MOTORS_TRI_SERVO_RANGE_DEG_MIN, AP_MOTORS_TRI_SERVO_RANGE_DEG_MAX); _yaw_servo_angle_max_deg.set(constrain_float(_yaw_servo_angle_max_deg, AP_MOTORS_TRI_SERVO_RANGE_DEG_MIN, AP_MOTORS_TRI_SERVO_RANGE_DEG_MAX));
// apply voltage and air pressure compensation // apply voltage and air pressure compensation
const float compensation_gain = get_compensation_gain(); const float compensation_gain = get_compensation_gain();