From de1dec819cee357378abd57c8957cfc3b4cbe46a Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sun, 27 Sep 2020 18:43:26 +0100 Subject: [PATCH] Rover: calc_steering_from_turn_rate remove args --- Rover/mode.cpp | 7 ++++--- Rover/mode.h | 5 +++-- 2 files changed, 7 insertions(+), 5 deletions(-) diff --git a/Rover/mode.cpp b/Rover/mode.cpp index 6c6f31c64a..0f278a310b 100644 --- a/Rover/mode.cpp +++ b/Rover/mode.cpp @@ -433,12 +433,13 @@ void Mode::navigate_to_waypoint() calc_steering_to_heading(desired_heading_cd, turn_rate); } else { // 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 -void Mode::calc_steering_from_turn_rate(float turn_rate, float speed, bool reversed) +// calculate steering output given a turn rate +// 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 const float steering_out = attitude_control.get_steering_out_rate(turn_rate, diff --git a/Rover/mode.h b/Rover/mode.h index b62752f7fe..44fd263d36 100644 --- a/Rover/mode.h +++ b/Rover/mode.h @@ -164,8 +164,9 @@ protected: // high level call to navigate to waypoint void navigate_to_waypoint(); - // calculate steering output given a turn rate and speed - void calc_steering_from_turn_rate(float turn_rate, float speed, bool reversed); + // calculate steering output given a turn rate + // 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 void calc_steering_from_lateral_acceleration(float lat_accel, bool reversed = false);