mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Rover: set reverse to false on entering a mode
This commit is contained in:
parent
289fe6c391
commit
8b9b1fdb66
@ -42,7 +42,14 @@ bool Mode::enter()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
return _enter();
|
bool ret = _enter();
|
||||||
|
|
||||||
|
// initialisation common to all modes
|
||||||
|
if (ret) {
|
||||||
|
set_reversed(false);
|
||||||
|
}
|
||||||
|
|
||||||
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
// decode pilot steering and throttle inputs and return in steer_out and throttle_out arguments
|
// decode pilot steering and throttle inputs and return in steer_out and throttle_out arguments
|
||||||
|
Loading…
Reference in New Issue
Block a user