Browse Source

Rover: accept do-change-speed commands with high speeds

master
Randy Mackay 7 years ago
parent
commit
631d8f5423
  1. 3
      APMrover2/commands_logic.cpp

3
APMrover2/commands_logic.cpp

@ -375,8 +375,7 @@ bool Rover::verify_within_distance()
void Rover::do_change_speed(const AP_Mission::Mission_Command& cmd) void Rover::do_change_speed(const AP_Mission::Mission_Command& cmd)
{ {
// set speed for active mode // set speed for active mode
if ((cmd.content.speed.target_ms >= 0.0f) && (cmd.content.speed.target_ms <= rover.control_mode->get_speed_default())) { if (control_mode->set_desired_speed(cmd.content.speed.target_ms)) {
control_mode->set_desired_speed(cmd.content.speed.target_ms);
gcs().send_text(MAV_SEVERITY_INFO, "speed: %.1f m/s", static_cast<double>(cmd.content.speed.target_ms)); gcs().send_text(MAV_SEVERITY_INFO, "speed: %.1f m/s", static_cast<double>(cmd.content.speed.target_ms));
} }
} }

Loading…
Cancel
Save