Browse Source

AC_AttControl: trad heli yaw

master
Randy Mackay 11 years ago committed by Andrew Tridgell
parent
commit
ebbff24a04
  1. 36
      libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp
  2. 1
      libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h

36
libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp

@ -112,7 +112,7 @@ void AC_AttitudeControl_Heli::rate_bf_to_motor_roll_pitch(float rate_roll_target
pitch_i = _pid_rate_pitch.get_i(rate_pitch_error, _dt); pitch_i = _pid_rate_pitch.get_i(rate_pitch_error, _dt);
} }
}else{ }else{
if (_flags_heli.leaky_i){ if (_flags_heli.leaky_i) {
pitch_i = _pid_rate_pitch.get_leaky_i(rate_pitch_error, _dt, AC_ATTITUDE_HELI_RATE_INTEGRATOR_LEAK_RATE); pitch_i = _pid_rate_pitch.get_leaky_i(rate_pitch_error, _dt, AC_ATTITUDE_HELI_RATE_INTEGRATOR_LEAK_RATE);
}else{ }else{
pitch_i = _pid_rate_pitch.get_i(rate_pitch_error, _dt); pitch_i = _pid_rate_pitch.get_i(rate_pitch_error, _dt);
@ -217,9 +217,10 @@ void AC_AttitudeControl_Heli::rate_bf_to_motor_roll_pitch(float rate_roll_target
// rate_bf_to_motor_yaw - ask the rate controller to calculate the motor outputs to achieve the target rate in centi-degrees / second // rate_bf_to_motor_yaw - ask the rate controller to calculate the motor outputs to achieve the target rate in centi-degrees / second
float AC_AttitudeControl_Heli::rate_bf_to_motor_yaw(float rate_target_cds) float AC_AttitudeControl_Heli::rate_bf_to_motor_yaw(float rate_target_cds)
{ {
float p,i,d; // used to capture pid values for logging float pd,i; // used to capture pid values for logging
float current_rate; // this iteration's rate float current_rate; // this iteration's rate
float rate_error; // simply target_rate - current_rate float rate_error; // simply target_rate - current_rate
float yaw_out;
// get current rate // get current rate
// To-Do: make getting gyro rates more efficient? // To-Do: make getting gyro rates more efficient?
@ -227,29 +228,36 @@ float AC_AttitudeControl_Heli::rate_bf_to_motor_yaw(float rate_target_cds)
// calculate error and call pid controller // calculate error and call pid controller
rate_error = rate_target_cds - current_rate; rate_error = rate_target_cds - current_rate;
p = _pid_rate_yaw.get_p(rate_error); pd = _pid_rate_yaw.get_p(rate_error) + _pid_rate_yaw.get_d(rate_error, _dt);
// separately calculate p, i, d values for logging
p = _pid_rate_yaw.get_p(rate_error);
// get i term // get i term
i = _pid_rate_yaw.get_integrator(); i = _pid_rate_yaw.get_integrator();
// update i term as long as we haven't breached the limits or the I term will certainly reduce // update i term as long as we haven't breached the limits or the I term will certainly reduce
if (!_motors.limit.yaw || ((i>0&&rate_error<0)||(i<0&&rate_error>0))) { if (!_flags_heli.limit_yaw || ((i>0&&rate_error<0)||(i<0&&rate_error>0))) {
i = _pid_rate_yaw.get_i(rate_error, _dt); AP_MotorsHeli& heli_motors = (AP_MotorsHeli&)_motors;
if (heli_motors.motor_runup_complete()) {
i = _pid_rate_yaw.get_i(rate_error, _dt);
} else {
i = _pid_rate_yaw.get_leaky_i(rate_error, _dt, AC_ATTITUDE_HELI_RATE_INTEGRATOR_LEAK_RATE); // If motor is not running use leaky I-term to avoid excessive build-up
}
} }
// get d value // add feed forward
d = _pid_rate_yaw.get_d(rate_error, _dt); yaw_out = (_heli_yaw_ff*rate_target_cds) + pd + i;
// constrain output and return // constrain output and update limit flag
return constrain_float((p+i+d), -AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX, AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX); if (fabs(yaw_out) > AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX) {
yaw_out = constrain_float(yaw_out,-AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX,AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX);
_flags_heli.limit_yaw = true;
}else{
_flags_heli.limit_yaw = false;
}
// To-Do: allow logging of PIDs? // output to motors
return yaw_out;
} }
// //
// throttle functions // throttle functions
// //

1
libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h

@ -47,6 +47,7 @@ private:
struct AttControlHeliFlags { struct AttControlHeliFlags {
uint8_t limit_roll : 1; // 1 if we have requested larger roll angle than swash can physically move uint8_t limit_roll : 1; // 1 if we have requested larger roll angle than swash can physically move
uint8_t limit_pitch : 1; // 1 if we have requested larger pitch angle than swash can physically move uint8_t limit_pitch : 1; // 1 if we have requested larger pitch angle than swash can physically move
uint8_t limit_yaw : 1; // 1 if we have requested larger yaw angle than tail servo can physically move
uint8_t leaky_i : 1; // 1 if we should use leaky i term for body-frame rate to motor stage uint8_t leaky_i : 1; // 1 if we should use leaky i term for body-frame rate to motor stage
} _flags_heli; } _flags_heli;

Loading…
Cancel
Save