Rover: calc_steering_from_turn_rate remove args

This commit is contained in:
Iampete1 2020-09-27 18:43:26 +01:00 committed by Randy Mackay
parent f33d197b16
commit de1dec819c
2 changed files with 7 additions and 5 deletions

View File

@ -433,12 +433,13 @@ void Mode::navigate_to_waypoint()
calc_steering_to_heading(desired_heading_cd, turn_rate); calc_steering_to_heading(desired_heading_cd, turn_rate);
} else { } else {
// call turn rate steering controller // call turn rate steering controller
calc_steering_from_turn_rate(g2.wp_nav.get_turn_rate_rads(), desired_speed, g2.wp_nav.get_reversed()); calc_steering_from_turn_rate(g2.wp_nav.get_turn_rate_rads());
} }
} }
// calculate steering output given a turn rate and speed // calculate steering output given a turn rate
void Mode::calc_steering_from_turn_rate(float turn_rate, float speed, bool reversed) // desired turn rate in radians/sec. Positive to the right.
void Mode::calc_steering_from_turn_rate(float turn_rate)
{ {
// calculate and send final steering command to motor library // calculate and send final steering command to motor library
const float steering_out = attitude_control.get_steering_out_rate(turn_rate, const float steering_out = attitude_control.get_steering_out_rate(turn_rate,

View File

@ -164,8 +164,9 @@ protected:
// high level call to navigate to waypoint // high level call to navigate to waypoint
void navigate_to_waypoint(); void navigate_to_waypoint();
// calculate steering output given a turn rate and speed // calculate steering output given a turn rate
void calc_steering_from_turn_rate(float turn_rate, float speed, bool reversed); // desired turn rate in radians/sec. Positive to the right.
void calc_steering_from_turn_rate(float turn_rate);
// calculate steering angle given a desired lateral acceleration // calculate steering angle given a desired lateral acceleration
void calc_steering_from_lateral_acceleration(float lat_accel, bool reversed = false); void calc_steering_from_lateral_acceleration(float lat_accel, bool reversed = false);