mirror of https://github.com/ArduPilot/ardupilot
AP_MotorsHeli: Change set_delta_phase_angle so that it forces recalculation of collective factors.
This commit is contained in:
parent
fd542e99d8
commit
789b1018fc
|
@ -787,3 +787,12 @@ void AP_MotorsHeli::write_aux(int16_t servo_out)
|
||||||
_servo_aux.calc_pwm();
|
_servo_aux.calc_pwm();
|
||||||
hal.rcout->write(AP_MOTORS_HELI_AUX, _servo_aux.radio_out);
|
hal.rcout->write(AP_MOTORS_HELI_AUX, _servo_aux.radio_out);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// set_delta_phase_angle for setting variable phase angle compensation and force
|
||||||
|
// recalculation of collective factors
|
||||||
|
void AP_MotorsHeli::set_delta_phase_angle(int16_t angle)
|
||||||
|
{
|
||||||
|
angle = constrain_int16(angle, -90, 90);
|
||||||
|
_delta_phase_angle = angle;
|
||||||
|
calculate_roll_pitch_collective_factors();
|
||||||
|
}
|
|
@ -195,8 +195,9 @@ public:
|
||||||
// set_dt for setting main loop rate time
|
// set_dt for setting main loop rate time
|
||||||
void set_dt(float dt) { _dt = dt; }
|
void set_dt(float dt) { _dt = dt; }
|
||||||
|
|
||||||
// set_dt for setting main loop rate time
|
// set_delta_phase_angle for setting variable phase angle compensation and force
|
||||||
void set_delta_phase_angle(int16_t angle) { _delta_phase_angle = angle; }
|
// recalculation of collective factors
|
||||||
|
void set_delta_phase_angle(int16_t angle);
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue