AC_AttitudeControl: correct bugs found in review

This commit is contained in:
Jonathan Challinger 2015-11-27 15:31:16 -08:00 committed by Randy Mackay
parent 9208003aab
commit bba360ea2b
3 changed files with 5 additions and 5 deletions

View File

@ -122,7 +122,7 @@ void AC_AttitudeControl::euler_angle_roll_pitch_euler_rate_yaw_smooth(float eule
// When acceleration limiting and feedforward are not enabled, the target roll euler angle is simply set to the
// input value and the feedforward rate is zeroed.
_att_target_euler_rad.x = euler_roll_angle_rad;
att_error_euler_rad.x = wrap_180_cd_float(_att_target_euler_rad.x - _ahrs.roll);
att_error_euler_rad.x = wrap_PI(_att_target_euler_rad.x - _ahrs.roll);
_att_target_euler_deriv_rads.x = 0;
}
_att_target_euler_rad.x = constrain_float(_att_target_euler_rad.x, -get_tilt_limit_rad(), get_tilt_limit_rad());
@ -141,7 +141,7 @@ void AC_AttitudeControl::euler_angle_roll_pitch_euler_rate_yaw_smooth(float eule
update_att_target_and_error_pitch(_att_target_euler_deriv_rads.y, att_error_euler_rad, AC_ATTITUDE_RATE_STAB_ROLL_OVERSHOOT_ANGLE_MAX_RAD);
} else {
_att_target_euler_rad.y = euler_pitch_angle_rad;
att_error_euler_rad.y = wrap_180_cd_float(_att_target_euler_rad.y - _ahrs.pitch);
att_error_euler_rad.y = wrap_PI(_att_target_euler_rad.y - _ahrs.pitch);
_att_target_euler_deriv_rads.y = 0;
}
_att_target_euler_rad.y = constrain_float(_att_target_euler_rad.y, -get_tilt_limit_rad(), get_tilt_limit_rad());

View File

@ -204,7 +204,7 @@ public:
virtual float get_althold_lean_angle_max() const = 0;
// Return configured tilt angle limit in centidegrees/s
int16_t lean_angle_max() const { return _aparm.angle_max; }
float lean_angle_max() const { return _aparm.angle_max; }
// Proportional controller with piecewise sqrt sections to constrain second derivative
static float sqrt_controller(float error, float p, float second_ord_lim);
@ -242,7 +242,7 @@ protected:
// Return angle in radians to be added to roll angle. Used by heli to counteract
// tail rotor thrust in hover. Overloaded by AC_Attitude_Heli to return angle.
virtual int16_t get_roll_trim_rad() { return 0;}
virtual float get_roll_trim_rad() { return 0;}
// Return the roll axis acceleration limit in radians/s/s
float get_accel_roll_max_radss() { return radians(_accel_roll_max*0.01f); }

View File

@ -115,7 +115,7 @@ private:
int16_t _passthrough_yaw;
// get_roll_trim - angle in centi-degrees to be added to roll angle. Used by helicopter to counter tail rotor thrust in hover
int16_t get_roll_trim_rad() { return radians(constrain_int16(_hover_roll_trim_scalar * _hover_roll_trim, -1000, 1000)*0.01f);}
float get_roll_trim_rad() { return constrain_float(radians(_hover_roll_trim_scalar * _hover_roll_trim * 0.01f), -radians(10.0f),radians(10.0f));}
// internal variables
float _hover_roll_trim_scalar = 0; // scalar used to suppress Hover Roll Trim