mirror of https://github.com/ArduPilot/ardupilot
Rover: accept do-change-speed commands with high speeds
This commit is contained in:
parent
4e0e159486
commit
c622783677
|
@ -375,8 +375,7 @@ bool Rover::verify_within_distance()
|
|||
void Rover::do_change_speed(const AP_Mission::Mission_Command& cmd)
|
||||
{
|
||||
// set speed for active mode
|
||||
if ((cmd.content.speed.target_ms >= 0.0f) && (cmd.content.speed.target_ms <= rover.control_mode->get_speed_default())) {
|
||||
control_mode->set_desired_speed(cmd.content.speed.target_ms);
|
||||
if (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));
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue