Browse Source

Rover: bug fix to steering mode top speed

Also non-functional change to calc_throttle to make call to calc_speed_nudge consistent
master
Randy Mackay 8 years ago
parent
commit
c9927e6af6
  1. 2
      APMrover2/mode.cpp
  2. 2
      APMrover2/mode_steering.cpp

2
APMrover2/mode.cpp

@ -68,7 +68,7 @@ void Mode::calc_throttle(float target_speed, bool nudge_allowed)
{ {
// add in speed nudging // add in speed nudging
if (nudge_allowed) { 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 // call throttle controller and convert output to -100 to +100 range

2
APMrover2/mode_steering.cpp

@ -4,7 +4,7 @@
void ModeSteering::update() void ModeSteering::update()
{ {
// convert pilot throttle input to desired speed (up to twice the cruise speed) // 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 // get speed forward
float speed; float speed;

Loading…
Cancel
Save