From 789b1018fcac733bfa97a2cad5e6d823158c7003 Mon Sep 17 00:00:00 2001 From: Robert Lefebvre Date: Sun, 11 May 2014 19:50:03 -0400 Subject: [PATCH] AP_MotorsHeli: Change set_delta_phase_angle so that it forces recalculation of collective factors. --- libraries/AP_Motors/AP_MotorsHeli.cpp | 9 +++++++++ libraries/AP_Motors/AP_MotorsHeli.h | 5 +++-- 2 files changed, 12 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsHeli.cpp b/libraries/AP_Motors/AP_MotorsHeli.cpp index e4f6f4ba52..39102e716d 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli.cpp @@ -787,3 +787,12 @@ void AP_MotorsHeli::write_aux(int16_t servo_out) _servo_aux.calc_pwm(); 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(); +} \ No newline at end of file diff --git a/libraries/AP_Motors/AP_MotorsHeli.h b/libraries/AP_Motors/AP_MotorsHeli.h index 117c6f8966..60191bac2e 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.h +++ b/libraries/AP_Motors/AP_MotorsHeli.h @@ -195,8 +195,9 @@ public: // set_dt for setting main loop rate time void set_dt(float dt) { _dt = dt; } - // set_dt for setting main loop rate time - void set_delta_phase_angle(int16_t angle) { _delta_phase_angle = angle; } + // set_delta_phase_angle for setting variable phase angle compensation and force + // recalculation of collective factors + void set_delta_phase_angle(int16_t angle); protected: