Browse Source

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
master
Randy Mackay 8 years ago
parent
commit
4fe937b985
  1. 4
      APMrover2/commands_logic.cpp
  2. 3
      APMrover2/mode_rtl.cpp

4
APMrover2/commands_logic.cpp

@ -215,9 +215,7 @@ bool Rover::verify_command(const AP_Mission::Mission_Command& cmd) @@ -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
APMrover2/mode_rtl.cpp

@ -3,7 +3,8 @@ @@ -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…
Cancel
Save