|
|
|
@ -319,24 +319,20 @@ void Copter::Mode::update_navigation()
@@ -319,24 +319,20 @@ void Copter::Mode::update_navigation()
|
|
|
|
|
|
|
|
|
|
// get_pilot_desired_angle - transform pilot's roll or pitch input into a desired lean angle
|
|
|
|
|
// returns desired angle in centi-degrees
|
|
|
|
|
void Copter::Mode::get_pilot_desired_lean_angles(float roll_in, float pitch_in, float &roll_out, float &pitch_out, float angle_max) |
|
|
|
|
void Copter::Mode::get_pilot_desired_lean_angles(float roll_in, float pitch_in, float &roll_out, float &pitch_out, float angle_max, float angle_limit) |
|
|
|
|
{ |
|
|
|
|
AP_Vehicle::MultiCopter &aparm = copter.aparm; |
|
|
|
|
// sanity check angle max parameter
|
|
|
|
|
aparm.angle_max = constrain_int16(aparm.angle_max,1000,8000); |
|
|
|
|
|
|
|
|
|
// limit max lean angle
|
|
|
|
|
angle_max = constrain_float(angle_max, 1000, aparm.angle_max); |
|
|
|
|
angle_limit = constrain_float(angle_limit, 1000.0f, angle_max); |
|
|
|
|
|
|
|
|
|
// scale roll_in, pitch_in to ANGLE_MAX parameter range
|
|
|
|
|
const float scaler = aparm.angle_max/(float)ROLL_PITCH_YAW_INPUT_MAX; |
|
|
|
|
float scaler = angle_max/(float)ROLL_PITCH_YAW_INPUT_MAX; |
|
|
|
|
roll_in *= scaler; |
|
|
|
|
pitch_in *= scaler; |
|
|
|
|
|
|
|
|
|
// do circular limit
|
|
|
|
|
const float total_in = norm(pitch_in, roll_in); |
|
|
|
|
if (total_in > angle_max) { |
|
|
|
|
float ratio = angle_max / total_in; |
|
|
|
|
float total_in = norm(pitch_in, roll_in); |
|
|
|
|
if (total_in > angle_limit) { |
|
|
|
|
float ratio = angle_limit / total_in; |
|
|
|
|
roll_in *= ratio; |
|
|
|
|
pitch_in *= ratio; |
|
|
|
|
} |
|
|
|
|