APM:Copter
mode_loiter.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 /*
4  * Init and run calls for loiter flight mode
5  */
6 
7 // loiter_init - initialise loiter controller
8 bool Copter::ModeLoiter::init(bool ignore_checks)
9 {
10  if (copter.position_ok() || ignore_checks) {
11 
12  // set target to current position
14 
15  // initialise position and desired velocity
16  if (!pos_control->is_active_z()) {
19  }
20 
21  return true;
22  }else{
23  return false;
24  }
25 }
26 
27 #if PRECISION_LANDING == ENABLED
29 {
31  return false;
32  }
33  if (ap.land_complete_maybe) {
34  return false; // don't move on the ground
35  }
36  // if the pilot *really* wants to move the vehicle, let them....
38  return false;
39  }
40  if (!copter.precland.target_acquired()) {
41  return false; // we don't have a good vector
42  }
43  return true;
44 }
45 
47 {
49  Vector2f target_pos, target_vel_rel;
50  if (!copter.precland.get_target_position_cm(target_pos)) {
51  target_pos.x = inertial_nav.get_position().x;
52  target_pos.y = inertial_nav.get_position().y;
53  }
54  if (!copter.precland.get_target_velocity_relative_cms(target_vel_rel)) {
55  target_vel_rel.x = -inertial_nav.get_velocity().x;
56  target_vel_rel.y = -inertial_nav.get_velocity().y;
57  }
58  pos_control->set_xy_target(target_pos.x, target_pos.y);
59  pos_control->override_vehicle_velocity_xy(-target_vel_rel);
60 }
61 #endif
62 
63 // loiter_run - runs the loiter controller
64 // should be called at 100hz or more
66 {
67  LoiterModeState loiter_state;
68 
69  float target_roll, target_pitch;
70  float target_yaw_rate = 0.0f;
71  float target_climb_rate = 0.0f;
72  float takeoff_climb_rate = 0.0f;
73 
74  // initialize vertical speed and acceleration
77 
78  // process pilot inputs unless we are in radio failsafe
79  if (!copter.failsafe.radio) {
80  // apply SIMPLE mode transform to pilot inputs
82 
83  // convert pilot input to lean angles
84  get_pilot_desired_lean_angles(target_roll, target_pitch, loiter_nav->get_angle_max_cd(), attitude_control->get_althold_lean_angle_max());
85 
86  // process pilot's roll and pitch input
87  loiter_nav->set_pilot_desired_acceleration(target_roll, target_pitch, G_Dt);
88 
89  // get pilot's desired yaw rate
91 
92  // get pilot desired climb rate
94  target_climb_rate = constrain_float(target_climb_rate, -get_pilot_speed_dn(), g.pilot_speed_up);
95  } else {
96  // clear out pilot desired acceleration in case radio failsafe event occurs and we do not switch to RTL for some reason
98  }
99 
100  // relax loiter target if we might be landed
101  if (ap.land_complete_maybe) {
103  }
104 
105  // Loiter State Machine Determination
106  if (!motors->armed() || !motors->get_interlock()) {
107  loiter_state = Loiter_MotorStopped;
108  } else if (takeoff_state.running || takeoff_triggered(target_climb_rate)) {
109  loiter_state = Loiter_Takeoff;
110  } else if (!ap.auto_armed || ap.land_complete) {
111  loiter_state = Loiter_Landed;
112  } else {
113  loiter_state = Loiter_Flying;
114  }
115 
116  // Loiter State Machine
117  switch (loiter_state) {
118 
119  case Loiter_MotorStopped:
120 
121  motors->set_desired_spool_state(AP_Motors::DESIRED_SHUT_DOWN);
122 #if FRAME_CONFIG == HELI_FRAME
123  // force descent rate and call position controller
125 #else
127  attitude_control->reset_rate_controller_I_terms();
128  attitude_control->set_yaw_target_to_current_heading();
129  pos_control->relax_alt_hold_controllers(0.0f); // forces throttle output to go to zero
130 #endif
132  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(loiter_nav->get_roll(), loiter_nav->get_pitch(), target_yaw_rate);
134  break;
135 
136  case Loiter_Takeoff:
137  // set motors to full range
138  motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
139 
140  // initiate take-off
141  if (!takeoff_state.running) {
143  // indicate we are taking off
144  set_land_complete(false);
145  // clear i term when we're taking off
147  }
148 
149  // get takeoff adjusted pilot and takeoff climb rates
150  takeoff_get_climb_rates(target_climb_rate, takeoff_climb_rate);
151 
152  // get avoidance adjusted climb rate
153  target_climb_rate = get_avoidance_adjusted_climbrate(target_climb_rate);
154 
155  // run loiter controller
157 
158  // call attitude controller
159  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(loiter_nav->get_roll(), loiter_nav->get_pitch(), target_yaw_rate);
160 
161  // update altitude target and call position controller
162  pos_control->set_alt_target_from_climb_rate_ff(target_climb_rate, G_Dt, false);
163  pos_control->add_takeoff_climb_rate(takeoff_climb_rate, G_Dt);
165  break;
166 
167  case Loiter_Landed:
168  // set motors to spin-when-armed if throttle below deadzone, otherwise full range (but motors will only spin at min throttle)
169  if (target_climb_rate < 0.0f) {
170  motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
171  } else {
172  motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
173  }
175  attitude_control->reset_rate_controller_I_terms();
176  attitude_control->set_yaw_target_to_current_heading();
177  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(0, 0, 0);
178  pos_control->relax_alt_hold_controllers(0.0f); // forces throttle output to go to zero
180  break;
181 
182  case Loiter_Flying:
183 
184  // set motors to full range
185  motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
186 
187 #if PRECISION_LANDING == ENABLED
188  if (do_precision_loiter()) {
190  }
191 #endif
192 
193  // run loiter controller
195 
196  // call attitude controller
197  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(loiter_nav->get_roll(), loiter_nav->get_pitch(), target_yaw_rate);
198 
199  // adjust climb rate using rangefinder
200  if (copter.rangefinder_alt_ok()) {
201  // if rangefinder is ok, use surface tracking
202  target_climb_rate = get_surface_tracking_climb_rate(target_climb_rate, pos_control->get_alt_target(), G_Dt);
203  }
204 
205  // get avoidance adjusted climb rate
206  target_climb_rate = get_avoidance_adjusted_climbrate(target_climb_rate);
207 
208  // update altitude target and call position controller
209  pos_control->set_alt_target_from_climb_rate_ff(target_climb_rate, G_Dt, false);
211  break;
212  }
213 }
214 
216 {
218 }
219 
221 {
223 }
DESIRED_SPIN_WHEN_ARMED
virtual float get_velocity_z() const=0
float get_alt_target() const
bool takeoff_triggered(float target_climb_rate) const
Definition: mode.cpp:354
virtual const Vector3f & get_position() const=0
float get_surface_tracking_climb_rate(int16_t target_rate, float current_alt_target, float dt)
Definition: mode.cpp:548
LoiterModeState
Definition: defines.h:243
virtual void set_alt_target_from_climb_rate(float climb_rate_cms, float dt, bool force_descend)
void takeoff_get_climb_rates(float &pilot_climb_rate, float &takeoff_climb_rate)
Definition: mode.cpp:612
float get_avoidance_adjusted_climbrate(float target_rate)
Definition: mode.cpp:617
void update_z_controller()
uint16_t get_pilot_speed_dn(void)
Definition: mode.cpp:622
void update_simple_mode(void)
Definition: mode.cpp:573
void override_vehicle_velocity_xy(const Vector2f &vel_xy)
AC_AttitudeControl_t *& attitude_control
Definition: Copter.h:123
void init_target(const Vector3f &position)
float get_pilot_desired_climb_rate(float throttle_control)
Definition: mode.cpp:558
AP_Int16 pilot_speed_up
Definition: Parameters.h:416
float get_pilot_desired_yaw_rate(int16_t stick_angle)
Definition: mode.cpp:553
void soften_for_landing()
bool _precision_loiter_enabled
Definition: Copter.h:890
AP_Int16 pilot_accel_z
Definition: Parameters.h:417
AP_Float pilot_takeoff_alt
Definition: Parameters.h:389
void set_xy_target(float x, float y)
void add_takeoff_climb_rate(float climb_rate_cms, float dt)
void precision_loiter_xy()
Definition: mode_loiter.cpp:46
bool is_active_z() const
bool init(bool ignore_checks) override
Definition: mode_loiter.cpp:8
void update(float ekfGndSpdLimit, float ekfNavVelGainScaler)
void takeoff_timer_start(float alt_cm)
Definition: mode.cpp:602
int16_t get_control_in() const
int32_t get_bearing_to_target() const
void relax_alt_hold_controllers(float throttle_setting)
#define f(i)
void set_desired_velocity_z(float vel_z_cms)
uint32_t wp_distance() const override
AP_Int16 land_speed
Definition: Parameters.h:414
void set_speed_z(float speed_down, float speed_up)
void set_throttle_takeoff(void)
Definition: mode.cpp:597
int32_t wp_bearing() const override
Vector2f get_pilot_desired_acceleration() const
void set_accel_z(float accel_cmss)
void get_pilot_desired_lean_angles(float &roll_out, float &pitch_out, float angle_max, float angle_limit) const
Definition: mode.cpp:326
DESIRED_THROTTLE_UNLIMITED
virtual void set_alt_target_from_climb_rate_ff(float climb_rate_cms, float dt, bool force_descend)
AC_PosControl *& pos_control
Definition: Copter.h:120
bool do_precision_loiter()
Definition: mode_loiter.cpp:28
float length(void) const
takeoff_state_t & takeoff_state
Definition: Copter.h:131
float constrain_float(const float amt, const float low, const float high)
void run() override
Definition: mode_loiter.cpp:65
void clear_pilot_desired_acceleration()
MOTOR_CLASS *& motors
Definition: Copter.h:124
AP_HAL_MAIN_CALLBACKS & copter
Definition: ArduCopter.cpp:581
float & G_Dt
Definition: Copter.h:129
void set_pilot_desired_acceleration(float euler_roll_angle_cd, float euler_pitch_angle_cd, float dt)
float & ekfNavVelGainScaler
Definition: Copter.h:137
AP_InertialNav & inertial_nav
Definition: Copter.h:121
virtual const Vector3f & get_velocity() const=0
float get_distance_to_target() const
RC_Channel *& channel_yaw
Definition: Copter.h:128
int32_t get_pitch() const
Parameters & g
Definition: Copter.h:116
int32_t get_roll() const
float & ekfGndSpdLimit
Definition: Copter.h:134
void set_land_complete(bool b)
Definition: mode.cpp:582
RC_Channel *& channel_throttle
Definition: Copter.h:127
AC_Loiter *& loiter_nav
Definition: Copter.h:119
void set_alt_target_to_current_alt()
float get_angle_max_cd() const