mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Rover: do_RTL calls set_mode(RTL)
This reverses the caller so the vehicle code calls into the mode instead of the mode calling up into the vehicle code
This commit is contained in:
parent
e7424a456f
commit
4fe937b985
@ -215,9 +215,7 @@ bool Rover::verify_command(const AP_Mission::Mission_Command& cmd)
|
||||
|
||||
void Rover::do_RTL(void)
|
||||
{
|
||||
prev_WP = current_loc;
|
||||
control_mode = &mode_rtl;
|
||||
next_WP = home;
|
||||
set_mode(mode_rtl);
|
||||
}
|
||||
|
||||
void Rover::do_nav_wp(const AP_Mission::Mission_Command& cmd)
|
||||
|
@ -3,7 +3,8 @@
|
||||
|
||||
bool ModeRTL::_enter()
|
||||
{
|
||||
rover.do_RTL();
|
||||
rover.prev_WP = rover.current_loc;
|
||||
rover.next_WP = rover.home;
|
||||
g2.motors.slew_limit_throttle(true);
|
||||
return true;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user