AC_AttControl: accessor for lean angle max

This commit is contained in:
Randy Mackay 2014-01-18 11:54:23 +09:00 committed by Andrew Tridgell
parent bbcf8cc84c
commit 9fe4d883d0
2 changed files with 8 additions and 5 deletions

View File

@ -148,7 +148,7 @@ void AC_AttitudeControl::rate_stab_ef_to_rate_ef_roll()
// ensure targets are within the lean angle limits
// To-Do: make angle_max part of the AP_Vehicle class
_angle_ef_target.x = constrain_float(_angle_ef_target.x, -aparm.angle_max, aparm.angle_max);
_angle_ef_target.x = constrain_float(_angle_ef_target.x, -_aparm.angle_max, _aparm.angle_max);
// calculate angle error with maximum of +- max_angle_overshoot
angle_error = wrap_180_cd(_angle_ef_target.x - _ahrs.roll_sensor);
@ -174,7 +174,7 @@ void AC_AttitudeControl::rate_stab_ef_to_rate_ef_pitch()
// ensure targets are within the lean angle limits
// To-Do: make angle_max part of the AP_Vehicle class
_angle_ef_target.y = constrain_float(_angle_ef_target.y, -aparm.angle_max, aparm.angle_max);
_angle_ef_target.y = constrain_float(_angle_ef_target.y, -_aparm.angle_max, _aparm.angle_max);
// calculate angle error with maximum of +- max_angle_overshoot
// To-Do: should we do something better as we cross 90 degrees?

View File

@ -35,7 +35,7 @@ class AC_AttitudeControl {
public:
AC_AttitudeControl( AP_AHRS &ahrs,
AP_InertialSensor& ins,
const AP_Vehicle::MultiCopter &parms,
const AP_Vehicle::MultiCopter &aparm,
AP_Motors& motors,
APM_PI& pi_angle_roll, APM_PI& pi_angle_pitch, APM_PI& pi_angle_yaw,
AC_PID& pid_rate_roll, AC_PID& pid_rate_pitch, AC_PID& pid_rate_yaw,
@ -43,7 +43,7 @@ public:
) :
_ahrs(ahrs),
_ins(ins),
aparm(parms),
_aparm(aparm),
_motors(motors),
_pi_angle_roll(pi_angle_roll),
_pi_angle_pitch(pi_angle_pitch),
@ -180,6 +180,9 @@ public:
_sin_pitch = sin_pitch;
}
// lean_angle_max - maximum lean angle of the copter in centi-degrees
int16_t lean_angle_max() { return _aparm.angle_max; }
// user settable parameters
static const struct AP_Param::GroupInfo var_info[];
@ -222,7 +225,7 @@ private:
// references to external libraries
AP_AHRS& _ahrs;
AP_InertialSensor& _ins;
const AP_Vehicle::MultiCopter &aparm;
const AP_Vehicle::MultiCopter &_aparm;
AP_Motors& _motors;
APM_PI& _pi_angle_roll;
APM_PI& _pi_angle_pitch;