AR_AttitudeControl: minor arg name fix

non-functional change
This commit is contained in:
Randy Mackay 2018-01-04 14:18:59 +09:00
parent 8f8917369c
commit 2aeda48512

View File

@ -43,14 +43,14 @@ public:
// return a steering servo output from -1.0 to +1.0 given a desired lateral acceleration rate in m/s/s.
// positive lateral acceleration is to the right.
float get_steering_out_lat_accel(float desired_accel, bool skid_steering, bool motor_limit_left, bool motor_limit_right, bool reverse);
float get_steering_out_lat_accel(float desired_accel, bool skid_steering, bool motor_limit_left, bool motor_limit_right, bool reversed);
// return a steering servo output from -1 to +1 given a yaw error in radians
float get_steering_out_angle_error(float angle_err, bool skid_steering, bool motor_limit_left, bool motor_limit_right, bool reversed);
// return a steering servo output from -1 to +1 given a
// desired yaw rate in radians/sec. Positive yaw is to the right.
float get_steering_out_rate(float desired_rate, bool skid_steering, bool motor_limit_left, bool motor_limit_right, bool reverse);
float get_steering_out_rate(float desired_rate, bool skid_steering, bool motor_limit_left, bool motor_limit_right, bool reversed);
// get latest desired turn rate in rad/sec recorded during calls to get_steering_out_rate. For reporting purposes only
float get_desired_turn_rate() const;