Rover: fix speed nudge

Problem: vehicle speed "runs away" to speed_max for any throttle value over 75%.
Cause: the desired_speed was calculated by interpolation between the current speed to speed_max, rather than the speed_default to speed_max. As current speed increases the desired speed increases although throttle is fixed. Hence the "runaway".

Fix: Now speed nudge interpolates between the desired speed and speed_max.

Tested:
modes:  wp navigation, guided ,rtl
params: spped_max, wp_speed, rtl_speed, speed_max
do_change_speed
This commit is contained in:
Guy Rodnay 2020-09-30 17:56:27 +03:00 committed by Randy Mackay
parent 8b3cc0b255
commit 8c32392d73
1 changed files with 1 additions and 1 deletions

View File

@ -420,7 +420,7 @@ void Mode::navigate_to_waypoint()
_distance_to_destination = g2.wp_nav.get_distance_to_destination();
// pass speed to throttle controller after applying nudge from pilot
float desired_speed = g2.wp_nav.get_speed();
float desired_speed = g2.wp_nav.get_desired_speed();
desired_speed = calc_speed_nudge(desired_speed, g2.wp_nav.get_reversed());
calc_throttle(desired_speed, true);