mirror of
https://github.com/ArduPilot/ardupilot.git
synced 2026-02-06 04:06:55 +08:00
Sub: get-pilot-desired-lean-angle loses constraint
no longer required because AC_AttitudeControl performs the constraint
This commit is contained in:
committed by
Peter Barker
parent
99d757841b
commit
c0761591c7
@@ -5,7 +5,7 @@
|
||||
void Sub::get_pilot_desired_lean_angles(float roll_in, float pitch_in, float &roll_out, float &pitch_out, float angle_max)
|
||||
{
|
||||
// sanity check angle max parameter
|
||||
const float angle_max_cd = constrain_float(attitude_control.lean_angle_max_cd(), 1000, 8000);
|
||||
const float angle_max_cd = attitude_control.lean_angle_max_cd();
|
||||
|
||||
// limit max lean angle
|
||||
angle_max = constrain_float(angle_max, 1000, angle_max_cd);
|
||||
|
||||
Reference in New Issue
Block a user