mirror of
https://github.com/ArduPilot/ardupilot.git
synced 2026-02-05 09:54:22 +08:00
Rover: increase max pilot speed to 100m/s
This commit is contained in:
@@ -377,8 +377,8 @@ float Mode::calc_speed_max(float cruise_speed, float cruise_throttle) const
|
||||
speed_max = (1.0f / cruise_throttle) * cruise_speed;
|
||||
}
|
||||
|
||||
// constrain to 30m/s (108km/h) and return
|
||||
return constrain_float(speed_max, 0.0f, 30.0f);
|
||||
// constrain to 100m/s and return
|
||||
return constrain_float(speed_max, 0.0f, 100.0f);
|
||||
}
|
||||
|
||||
// calculate pilot input to nudge speed up or down
|
||||
|
||||
Reference in New Issue
Block a user