AR_AttitudeControl: remove constraint on steering output

This commit is contained in:
Randy Mackay 2018-06-08 13:16:16 +09:00
parent eb234a1306
commit e02375022e
2 changed files with 8 additions and 5 deletions

View File

@ -285,7 +285,7 @@ float AR_AttitudeControl::get_steering_out_rate(float desired_rate, bool motor_l
const float d = _steer_rate_pid.get_d();
// constrain and return final output
return constrain_float(ff + p + i + d, -1.0f, 1.0f);
return (ff + p + i + d);
}
// get latest desired turn rate in rad/sec (recorded during calls to get_steering_out_rate)

View File

@ -43,15 +43,18 @@ public:
// steering controller
//
// return a steering servo output from -1.0 to +1.0 given a desired lateral acceleration rate in m/s/s.
// return a steering servo output given a desired lateral acceleration rate in m/s/s.
// positive lateral acceleration is to the right. dt should normally be the main loop rate.
// return value is normally in range -1.0 to +1.0 but can be higher or lower
float get_steering_out_lat_accel(float desired_accel, bool motor_limit_left, bool motor_limit_right, float dt);
// return a steering servo output from -1 to +1 given a heading in radians
// return a steering servo output given a heading in radians
// return value is normally in range -1.0 to +1.0 but can be higher or lower
float get_steering_out_heading(float heading_rad, float rate_max, bool motor_limit_left, bool motor_limit_right, float dt);
// return a steering servo output from -1 to +1 given a
// desired yaw rate in radians/sec. Positive yaw is to the right.
// return a steering servo output given a desired yaw rate in radians/sec.
// positive yaw is to the right
// return value is normally in range -1.0 to +1.0 but can be higher or lower
float get_steering_out_rate(float desired_rate, bool motor_limit_left, bool motor_limit_right, float dt);
// get latest desired turn rate in rad/sec recorded during calls to get_steering_out_rate. For reporting purposes only