APM:Copter
mode_smart_rtl.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 #if MODE_SMARTRTL_ENABLED == ENABLED
4 
5 /*
6  * Init and run calls for Smart_RTL flight mode
7  *
8  * This code uses the SmartRTL path that is already in memory, and feeds it into WPNav, one point at a time.
9  * Once the copter is close to home, it will run a standard land controller.
10  */
11 
12 bool Copter::ModeSmartRTL::init(bool ignore_checks)
13 {
14  if ((copter.position_ok() || ignore_checks) && g2.smart_rtl.is_active()) {
15  // initialise waypoint and spline controller
17 
18  // set current target to a reasonable stopping point
19  Vector3f stopping_point;
20  pos_control->get_stopping_point_xy(stopping_point);
21  pos_control->get_stopping_point_z(stopping_point);
22  wp_nav->set_wp_destination(stopping_point);
23 
24  // initialise yaw to obey user parameter
26 
27  // wait for cleanup of return path
29  return true;
30  }
31 
32  return false;
33 }
34 
35 // perform cleanup required when leaving smart_rtl
37 {
39 }
40 
42 {
43  switch (smart_rtl_state) {
46  break;
49  break;
52  break;
53  case SmartRTL_Descend:
54  descent_run(); // Re-using the descend method from normal rtl mode.
55  break;
56  case SmartRTL_Land:
57  land_run(true); // Re-using the land method from normal rtl mode.
58  break;
59  }
60 }
61 
63 {
64  // hover at current target position
65  motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
68  attitude_control->input_euler_angle_roll_pitch_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), auto_yaw.yaw(),true);
69 
70  // check if return path is computed and if yes, begin journey home
73  }
74 }
75 
77 {
78  float target_yaw_rate = 0.0f;
79  if (!copter.failsafe.radio) {
80  // get pilot's desired yaw rate
82  if (!is_zero(target_yaw_rate)) {
84  }
85  }
86 
87  // if we are close to current target point, switch the next point to be our target.
89  Vector3f next_point;
90  if (g2.smart_rtl.pop_point(next_point)) {
91  bool fast_waypoint = true;
92  if (g2.smart_rtl.get_num_points() == 0) {
93  // this is the very last point, add 2m to the target alt and move to pre-land state
94  next_point.z -= 2.0f;
96  fast_waypoint = false;
97  }
98  // send target to waypoint controller
99  wp_nav->set_wp_destination_NED(next_point);
100  wp_nav->set_fast_waypoint(fast_waypoint);
101  } else {
102  // this can only happen if we fail to get the semaphore which should never happen but just in case, land
104  }
105  }
106 
107  // update controllers
108  motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
109  wp_nav->update_wpnav();
111 
112  // call attitude controller
113  if (auto_yaw.mode() == AUTO_YAW_HOLD) {
114  // roll & pitch from waypoint controller, yaw rate from pilot
115  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), target_yaw_rate);
116  } else {
117  // roll, pitch from waypoint controller, yaw heading from auto_heading()
118  attitude_control->input_euler_angle_roll_pitch_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), auto_yaw.yaw(), true);
119  }
120 }
121 
123 {
124  // if we are close to 2m above start point, we are ready to land.
126  // choose descend and hold, or land based on user parameter rtl_alt_final
127  if (g.rtl_alt_final <= 0 || copter.failsafe.radio) {
128  land_start();
130  } else {
131  set_descent_target_alt(copter.g.rtl_alt_final);
132  descent_start();
134  }
135  }
136 
137  // update controllers
138  motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
139  wp_nav->update_wpnav();
141  attitude_control->input_euler_angle_roll_pitch_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), auto_yaw.yaw(), true);
142 }
143 
144 // save current position for use by the smart_rtl flight mode
146 {
147  const bool should_save_position = motors->armed() && (copter.control_mode != SMART_RTL);
148 
149  copter.g2.smart_rtl.update(copter.position_ok(), should_save_position);
150 }
151 
153 {
155 }
156 
158 {
160 }
161 
162 #endif
void get_stopping_point_xy(Vector3f &stopping_point) const
bool reached_wp_destination() const
void land_run(bool disarm_on_land)
Definition: mode_rtl.cpp:353
void set_mode_to_default(bool rtl)
Definition: autoyaw.cpp:28
void land_start()
Definition: mode_rtl.cpp:320
int32_t get_pitch() const
void get_stopping_point_z(Vector3f &stopping_point) const
void update_z_controller()
SmartRTLState smart_rtl_state
Definition: Copter.h:1029
bool request_thorough_cleanup(ThoroughCleanupType clean_type=THOROUGH_CLEAN_DEFAULT)
uint32_t wp_distance() const override
AC_AttitudeControl_t *& attitude_control
Definition: Copter.h:123
void descent_run()
Definition: mode_rtl.cpp:258
float get_pilot_desired_yaw_rate(int16_t stick_angle)
Definition: mode.cpp:553
int32_t get_roll() const
void set_descent_target_alt(uint32_t alt)
Definition: Copter.h:967
bool set_wp_destination(const Location_Class &destination)
autopilot_yaw_mode mode() const
Definition: Copter.h:26
int32_t get_wp_bearing_to_destination() const
AP_Int16 rtl_alt_final
Definition: Parameters.h:403
bool is_active() const
bool update_wpnav()
void set_mode(autopilot_yaw_mode new_mode)
Definition: autoyaw.cpp:59
int16_t get_control_in() const
bool is_zero(const T fVal1)
ParametersG2 & g2
Definition: Copter.h:117
void set_fast_waypoint(bool fast)
uint16_t get_num_points() const
float get_wp_distance_to_destination() const
bool set_wp_destination_NED(const Vector3f &destination_NED)
AC_WPNav *& wp_nav
Definition: Copter.h:118
void wp_and_spline_init()
DESIRED_THROTTLE_UNLIMITED
AC_PosControl *& pos_control
Definition: Copter.h:120
int32_t wp_bearing() const override
bool pop_point(Vector3f &point)
MOTOR_CLASS *& motors
Definition: Copter.h:124
AP_HAL_MAIN_CALLBACKS & copter
Definition: ArduCopter.cpp:581
void cancel_request_for_thorough_cleanup()
static AutoYaw auto_yaw
Definition: Copter.h:73
RC_Channel *& channel_yaw
Definition: Copter.h:128
void run() override
Parameters & g
Definition: Copter.h:116
AP_SmartRTL smart_rtl
Definition: Parameters.h:570
void descent_start()
Definition: mode_rtl.cpp:241
bool init(bool ignore_checks) override