APM:Copter
mode_land.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 // FIXME? why are these static?
4 static bool land_with_gps;
5 
6 static uint32_t land_start_time;
7 static bool land_pause;
8 
9 // land_init - initialise land controller
10 bool Copter::ModeLand::init(bool ignore_checks)
11 {
12  // check if we have GPS and decide which LAND we're going to do
13  land_with_gps = copter.position_ok();
14  if (land_with_gps) {
15  // set target to stopping point
16  Vector3f stopping_point;
17  loiter_nav->get_stopping_point_xy(stopping_point);
18  loiter_nav->init_target(stopping_point);
19  }
20 
21  // initialize vertical speeds and leash lengths
24 
25  // initialise position and desired velocity
26  if (!pos_control->is_active_z()) {
29  }
30 
32 
33  land_pause = false;
34 
35  // reset flag indicating if pilot has applied roll or pitch inputs during landing
36  ap.land_repo_active = false;
37 
38  return true;
39 }
40 
41 // land_run - runs the land controller
42 // should be called at 100hz or more
44 {
45  if (land_with_gps) {
46  gps_run();
47  }else{
48  nogps_run();
49  }
50 }
51 
52 // land_gps_run - runs the land controller
53 // horizontal position controlled with loiter controller
54 // should be called at 100hz or more
56 {
57  // if not auto armed or landed or motor interlock not enabled set throttle to zero and exit immediately
58  if (!motors->armed() || !ap.auto_armed || ap.land_complete || !motors->get_interlock()) {
61 
62  // disarm when the landing detector says we've landed
63  if (ap.land_complete) {
64  copter.init_disarm_motors();
65  }
66  return;
67  }
68 
69  // set motors to full range
70  motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
71 
72  // pause before beginning land descent
74  land_pause = false;
75  }
76 
79 }
80 
81 // land_nogps_run - runs the land controller
82 // pilot controls roll and pitch angles
83 // should be called at 100hz or more
85 {
86  float target_roll = 0.0f, target_pitch = 0.0f;
87  float target_yaw_rate = 0;
88 
89  // process pilot inputs
90  if (!copter.failsafe.radio) {
91  if ((g.throttle_behavior & THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND) != 0 && copter.rc_throttle_control_in_filter.get() > LAND_CANCEL_TRIGGER_THR){
93  // exit land if throttle is high
95  }
96 
97  if (g.land_repositioning) {
98  // apply SIMPLE mode transform to pilot inputs
100 
101  // get pilot desired lean angles
102  get_pilot_desired_lean_angles(target_roll, target_pitch, copter.aparm.angle_max, attitude_control->get_althold_lean_angle_max());
103  }
104 
105  // get pilot's desired yaw rate
107  }
108 
109  // if not auto armed or landed or motor interlock not enabled set throttle to zero and exit immediately
110  if (!motors->armed() || !ap.auto_armed || ap.land_complete || !motors->get_interlock()) {
111 #if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
112  // call attitude controller
113  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
114  attitude_control->set_throttle_out(0,false,g.throttle_filt);
115 #else
116  motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
117  // multicopters do not stabilize roll/pitch/yaw when disarmed
118  attitude_control->set_throttle_out_unstabilized(0,true,g.throttle_filt);
119 #endif
120 
121  // disarm when the landing detector says we've landed
122  if (ap.land_complete) {
123  copter.init_disarm_motors();
124  }
125  return;
126  }
127 
128  // set motors to full range
129  motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
130 
131  // call attitude controller
132  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
133 
134  // pause before beginning land descent
136  land_pause = false;
137  }
138 
140 }
141 
142 // do_not_use_GPS - forces land-mode to not use the GPS but instead rely on pilot input for roll and pitch
143 // called during GPS failsafe to ensure that if we were already in LAND mode that we do not use the GPS
144 // has no effect if we are not already in LAND mode
146 {
147  land_with_gps = false;
148 }
149 
150 // set_mode_land_with_pause - sets mode to LAND and triggers 4 second delay before descent starts
151 // this is always called from a failsafe so we trigger notification to pilot
153 {
154  set_mode(LAND, reason);
155  land_pause = true;
156 
157  // alert pilot to mode change
159 }
160 
161 // landing_with_GPS - returns true if vehicle is landing using GPS
163 {
164  return (control_mode == LAND && land_with_gps);
165 }
DESIRED_SPIN_WHEN_ARMED
void zero_throttle_and_relax_ac()
Definition: mode.cpp:373
bool set_mode(control_mode_t mode, mode_reason_t reason)
Definition: mode.cpp:577
virtual float get_velocity_z() const=0
#define LAND_WITH_DELAY_MS
Definition: config.h:413
AP_Float throttle_filt
Definition: Parameters.h:386
static bool land_with_gps
Definition: mode_land.cpp:4
AP_Int16 throttle_behavior
Definition: Parameters.h:387
static bool land_pause
Definition: mode_land.cpp:7
void do_not_use_GPS()
Definition: mode_land.cpp:145
bool landing_with_GPS()
Definition: mode_land.cpp:162
void Log_Write_Event(uint8_t id)
Definition: mode.cpp:592
void update_simple_mode(void)
Definition: mode.cpp:573
float get_accel_z() const
void set_mode_land_with_pause(mode_reason_t reason)
Definition: mode_land.cpp:152
Definition: defines.h:100
AC_AttitudeControl_t *& attitude_control
Definition: Copter.h:123
void init_target(const Vector3f &position)
void run() override
Definition: mode_land.cpp:43
float get_pilot_desired_yaw_rate(int16_t stick_angle)
Definition: mode.cpp:553
float get_speed_down() const
mode_reason_t
Definition: defines.h:115
AP_Int8 land_repositioning
Definition: Parameters.h:452
void land_run_horizontal_control()
Definition: mode.cpp:449
void land_run_vertical_control(bool pause_descent=false)
Definition: mode.cpp:403
#define THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND
Definition: defines.h:484
bool is_active_z() const
void get_stopping_point_xy(Vector3f &stopping_point) const
int16_t get_control_in() const
void set_desired_velocity_z(float vel_z_cms)
void set_speed_z(float speed_down, float speed_up)
uint32_t millis()
float get_speed_up() const
AC_WPNav *& wp_nav
Definition: Copter.h:118
static uint32_t land_start_time
Definition: mode_land.cpp:6
void set_accel_z(float accel_cmss)
#define DATA_LAND_CANCELLED_BY_PILOT
Definition: defines.h:381
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
AC_PosControl *& pos_control
Definition: Copter.h:120
MOTOR_CLASS *& motors
Definition: Copter.h:124
AP_HAL_MAIN_CALLBACKS & copter
Definition: ArduCopter.cpp:581
#define LAND_CANCEL_TRIGGER_THR
Definition: config.h:416
AP_InertialNav & inertial_nav
Definition: Copter.h:121
RC_Channel *& channel_yaw
Definition: Copter.h:128
static struct notify_events_type events
control_mode_t control_mode
Definition: Copter.h:345
bool init(bool ignore_checks) override
Definition: mode_land.cpp:10
Parameters & g
Definition: Copter.h:116
AC_Loiter *& loiter_nav
Definition: Copter.h:119
void set_alt_target_to_current_alt()