From c9927e6af606d57a2464763d37a2d4d3fcca9146 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 16 Aug 2017 11:32:55 +0900 Subject: [PATCH] Rover: bug fix to steering mode top speed Also non-functional change to calc_throttle to make call to calc_speed_nudge consistent --- APMrover2/mode.cpp | 2 +- APMrover2/mode_steering.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/APMrover2/mode.cpp b/APMrover2/mode.cpp index e7af029d3c..b8701abcb9 100644 --- a/APMrover2/mode.cpp +++ b/APMrover2/mode.cpp @@ -68,7 +68,7 @@ void Mode::calc_throttle(float target_speed, bool nudge_allowed) { // add in speed nudging if (nudge_allowed) { - target_speed = calc_speed_nudge(target_speed, g.speed_cruise, g.throttle_cruise / 100.0f); + target_speed = calc_speed_nudge(target_speed, g.speed_cruise, g.throttle_cruise * 0.01f); } // call throttle controller and convert output to -100 to +100 range diff --git a/APMrover2/mode_steering.cpp b/APMrover2/mode_steering.cpp index a440773870..b1d5dba20b 100644 --- a/APMrover2/mode_steering.cpp +++ b/APMrover2/mode_steering.cpp @@ -4,7 +4,7 @@ void ModeSteering::update() { // convert pilot throttle input to desired speed (up to twice the cruise speed) - float target_speed = channel_throttle->get_control_in() * 0.01f * calc_speed_max(g.speed_cruise, g.throttle_cruise); + float target_speed = channel_throttle->get_control_in() * 0.01f * calc_speed_max(g.speed_cruise, g.throttle_cruise * 0.01f); // get speed forward float speed;