mirror of https://github.com/ArduPilot/ardupilot
22 lines
399 B
C++
22 lines
399 B
C++
#include "mode.h"
|
|
#include "Plane.h"
|
|
|
|
bool ModeRTL::_enter()
|
|
{
|
|
plane.throttle_allows_nudging = true;
|
|
plane.auto_throttle_mode = true;
|
|
plane.auto_navigation_mode = true;
|
|
plane.prev_WP_loc = plane.current_loc;
|
|
plane.do_RTL(plane.get_RTL_altitude());
|
|
|
|
return true;
|
|
}
|
|
|
|
void ModeRTL::update()
|
|
{
|
|
plane.calc_nav_roll();
|
|
plane.calc_nav_pitch();
|
|
plane.calc_throttle();
|
|
}
|
|
|