Rover: remove set of slew for motor test

The motor library test function does not attempt to implement slewing so setting this is not necessary
This commit is contained in:
Randy Mackay 2017-11-22 09:32:12 +09:00
parent ca72b20e04
commit 822c4b6dca

View File

@ -37,7 +37,6 @@ void Rover::set_servos(void)
{
// send output signals to motors
if (motor_test) {
g2.motors.slew_limit_throttle(false);
motor_test_output();
} else {
g2.motors.output(arming.is_armed() && hal.util->get_soft_armed(), G_Dt);