// rtl_init - initialise rtl controller bool Copter::ModeRTL::init(bool ignore_checks) { // initialise waypoint and spline controller wp_nav->wp_and_spline_init(); build_path(!copter.failsafe.terrain); climb_start(); return true; }
// re-start RTL with terrain following disabled void Copter::ModeRTL::restart_without_terrain() { AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::RESTARTED_RTL); if (rtl_path.terrain_used) { build_path(false); climb_start(); gcs().send_text(MAV_SEVERITY_CRITICAL,"Restarting RTL - Terrain data missing"); } }
// re-start RTL with terrain following disabled void Copter::ModeRTL::restart_without_terrain() { // log an error copter.Log_Write_Error(ERROR_SUBSYSTEM_NAVIGATION, ERROR_CODE_RESTARTED_RTL); if (rtl_path.terrain_used) { build_path(false); climb_start(); gcs().send_text(MAV_SEVERITY_CRITICAL,"Restarting RTL - Terrain data missing"); } }