APM:Copter
mode_throw.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 #if MODE_THROW_ENABLED == ENABLED
4 
5 // throw_init - initialise throw controller
6 bool Copter::ModeThrow::init(bool ignore_checks)
7 {
8 #if FRAME_CONFIG == HELI_FRAME
9  // do not allow helis to use throw to start
10  return false;
11 #endif
12 
13  // do not enter the mode when already armed or when flying
14  if (motors->armed()) {
15  return false;
16  }
17 
18  // init state
20  nextmode_attempted = false;
21 
22  return true;
23 }
24 
25 // runs the throw to start controller
26 // should be called at 100hz or more
28 {
29  /* Throw State Machine
30  Throw_Disarmed - motors are off
31  Throw_Detecting - motors are on and we are waiting for the throw
32  Throw_Uprighting - the throw has been detected and the copter is being uprighted
33  Throw_HgtStabilise - the copter is kept level and height is stabilised about the target height
34  Throw_PosHold - the copter is kept at a constant position and height
35  */
36 
37  // Don't enter THROW mode if interlock will prevent motors running
38  if (!motors->armed() && motors->get_interlock()) {
39  // state machine entry is always from a disarmed state
41 
42  } else if (stage == Throw_Disarmed && motors->armed()) {
43  gcs().send_text(MAV_SEVERITY_INFO,"waiting for throw");
45 
46  } else if (stage == Throw_Detecting && throw_detected()){
47  gcs().send_text(MAV_SEVERITY_INFO,"throw detected - uprighting");
49 
50  // Cancel the waiting for throw tone sequence
52 
53  } else if (stage == Throw_Uprighting && throw_attitude_good()) {
54  gcs().send_text(MAV_SEVERITY_INFO,"uprighted - controlling height");
56 
57  // initialize vertical speed and acceleration limits
58  // use brake mode values for rapid response
61 
62  // initialise the demanded height to 3m above the throw height
63  // we want to rapidly clear surrounding obstacles
64  if (g2.throw_type == ThrowType_Drop) {
66  } else {
68  }
69 
70  // set the initial velocity of the height controller demand to the measured velocity if it is going up
71  // if it is going down, set it to zero to enforce a very hard stop
73 
74  // Set the auto_arm status to true to avoid a possible automatic disarm caused by selection of an auto mode with throttle at minimum
75  copter.set_auto_armed(true);
76 
77  } else if (stage == Throw_HgtStabilise && throw_height_good()) {
78  gcs().send_text(MAV_SEVERITY_INFO,"height achieved - controlling position");
80 
81  // initialise the loiter target to the curent position and velocity
83 
84  // Set the auto_arm status to true to avoid a possible automatic disarm caused by selection of an auto mode with throttle at minimum
85  copter.set_auto_armed(true);
86  } else if (stage == Throw_PosHold && throw_position_good()) {
87  if (!nextmode_attempted) {
88  switch (g2.throw_nextmode) {
89  case AUTO:
90  case GUIDED:
91  case RTL:
92  case LAND:
93  case BRAKE:
94  case LOITER:
96  break;
97  default:
98  // do nothing
99  break;
100  }
101  nextmode_attempted = true;
102  }
103  }
104 
105  // Throw State Processing
106  switch (stage) {
107 
108  case Throw_Disarmed:
109 
110  // prevent motors from rotating before the throw is detected unless enabled by the user
111  if (g.throw_motor_start == 1) {
112  motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
113  } else {
114  motors->set_desired_spool_state(AP_Motors::DESIRED_SHUT_DOWN);
115  }
116 
117  // demand zero throttle (motors will be stopped anyway) and continually reset the attitude controller
118  attitude_control->set_throttle_out_unstabilized(0,true,g.throttle_filt);
119  break;
120 
121  case Throw_Detecting:
122 
123  // prevent motors from rotating before the throw is detected unless enabled by the user
124  if (g.throw_motor_start == 1) {
125  motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
126  } else {
127  motors->set_desired_spool_state(AP_Motors::DESIRED_SHUT_DOWN);
128  }
129 
130  // Hold throttle at zero during the throw and continually reset the attitude controller
131  attitude_control->set_throttle_out_unstabilized(0,true,g.throttle_filt);
132 
133  // Play the waiting for throw tone sequence to alert the user
135 
136  break;
137 
138  case Throw_Uprighting:
139 
140  // set motors to full range
141  motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
142 
143  // demand a level roll/pitch attitude with zero yaw rate
144  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(0.0f, 0.0f, 0.0f);
145 
146  // output 50% throttle and turn off angle boost to maximise righting moment
147  attitude_control->set_throttle_out(0.5f, false, g.throttle_filt);
148 
149  break;
150 
151  case Throw_HgtStabilise:
152 
153  // set motors to full range
154  motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
155 
156  // call attitude controller
157  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(0.0f, 0.0f, 0.0f);
158 
159  // call height controller
162 
163  break;
164 
165  case Throw_PosHold:
166 
167  // set motors to full range
168  motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
169 
170  // run loiter controller
172 
173  // call attitude controller
174  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(loiter_nav->get_roll(), loiter_nav->get_pitch(), 0.0f);
175 
176  // call height controller
179 
180  break;
181  }
182 
183  // log at 10hz or if stage changes
184  uint32_t now = AP_HAL::millis();
185  if ((stage != prev_stage) || (now - last_log_ms) > 100) {
186  prev_stage = stage;
187  last_log_ms = now;
188  const float velocity = inertial_nav.get_velocity().length();
189  const float velocity_z = inertial_nav.get_velocity().z;
190  const float accel = copter.ins.get_accel().length();
191  const float ef_accel_z = ahrs.get_accel_ef().z;
192  const bool throw_detect = (stage > Throw_Detecting) || throw_detected();
193  const bool attitude_ok = (stage > Throw_Uprighting) || throw_attitude_good();
194  const bool height_ok = (stage > Throw_HgtStabilise) || throw_height_good();
195  const bool pos_ok = (stage > Throw_PosHold) || throw_position_good();
197  "THRO",
198  "TimeUS,Stage,Vel,VelZ,Acc,AccEfZ,Throw,AttOk,HgtOk,PosOk",
199  "s-nnoo----",
200  "F-0000----",
201  "QBffffbbbb",
203  (uint8_t)stage,
204  (double)velocity,
205  (double)velocity_z,
206  (double)accel,
207  (double)ef_accel_z,
208  throw_detect,
209  attitude_ok,
210  height_ok,
211  pos_ok);
212  }
213 }
214 
216 {
217  // Check that we have a valid navigation solution
219  if (!filt_status.flags.attitude || !filt_status.flags.horiz_pos_abs || !filt_status.flags.vert_pos) {
220  return false;
221  }
222 
223  // Check for high speed (>500 cm/s)
224  bool high_speed = inertial_nav.get_velocity().length() > THROW_HIGH_SPEED;
225 
226  // check for upwards or downwards trajectory (airdrop) of 50cm/s
227  bool changing_height;
228  if (g2.throw_type == ThrowType_Drop) {
229  changing_height = inertial_nav.get_velocity().z < -THROW_VERTICAL_SPEED;
230  } else {
231  changing_height = inertial_nav.get_velocity().z > THROW_VERTICAL_SPEED;
232  }
233 
234  // Check the vertical acceleraton is greater than 0.25g
235  bool free_falling = ahrs.get_accel_ef().z > -0.25 * GRAVITY_MSS;
236 
237  // Check if the accel length is < 1.0g indicating that any throw action is complete and the copter has been released
238  bool no_throw_action = copter.ins.get_accel().length() < 1.0f * GRAVITY_MSS;
239 
240  // High velocity or free-fall combined with increasing height indicate a possible air-drop or throw release
241  bool possible_throw_detected = (free_falling || high_speed) && changing_height && no_throw_action;
242 
243  // Record time and vertical velocity when we detect the possible throw
244  if (possible_throw_detected && ((AP_HAL::millis() - free_fall_start_ms) > 500)) {
247  }
248 
249  // Once a possible throw condition has been detected, we check for 2.5 m/s of downwards velocity change in less than 0.5 seconds to confirm
250  bool throw_condition_confirmed = ((AP_HAL::millis() - free_fall_start_ms < 500) && ((inertial_nav.get_velocity().z - free_fall_start_velz) < -250.0f));
251 
252  // start motors and enter the control mode if we are in continuous freefall
253  if (throw_condition_confirmed) {
254  return true;
255  } else {
256  return false;
257  }
258 }
259 
261 {
262  // Check that we have uprighted the copter
263  const Matrix3f &rotMat = ahrs.get_rotation_body_to_ned();
264  return (rotMat.c.z > 0.866f); // is_upright
265 }
266 
268 {
269  // Check that we are within 0.5m of the demanded height
270  return (pos_control->get_alt_error() < 50.0f);
271 }
272 
274 {
275  // check that our horizontal position error is within 50cm
276  return (pos_control->get_horizontal_error() < 50.0f);
277 }
278 #endif
DESIRED_SPIN_WHEN_ARMED
bool set_mode(control_mode_t mode, mode_reason_t reason)
Definition: mode.cpp:577
virtual float get_velocity_z() const=0
control_mode_t
Definition: defines.h:91
AP_Float throttle_filt
Definition: Parameters.h:386
float get_alt_error() const
virtual nav_filter_status get_filter_status() const=0
void update_z_controller()
GCS_Copter & gcs()
Definition: mode.cpp:587
Definition: defines.h:95
Definition: defines.h:106
Definition: defines.h:96
Definition: defines.h:100
float get_horizontal_error() const
#define THROW_VERTICAL_SPEED
Definition: config.h:610
bool throw_height_good()
Definition: mode_throw.cpp:267
AC_AttitudeControl_t *& attitude_control
Definition: Copter.h:123
void init_target(const Vector3f &position)
virtual const Matrix3f & get_rotation_body_to_ned(void) const=0
ThrowModeStage prev_stage
Definition: Copter.h:1141
void update(float ekfGndSpdLimit, float ekfNavVelGainScaler)
#define THROW_HIGH_SPEED
Definition: config.h:607
uint32_t free_fall_start_ms
Definition: Copter.h:1144
void Log_Write(const char *name, const char *labels, const char *fmt,...)
#define GRAVITY_MSS
#define f(i)
ParametersG2 & g2
Definition: Copter.h:117
virtual const Vector3f & get_accel_ef(uint8_t i) const
void set_desired_velocity_z(float vel_z_cms)
void set_speed_z(float speed_down, float speed_up)
Vector3< float > c
uint32_t millis()
static DataFlash_Class * instance(void)
#define BRAKE_MODE_SPEED_Z
Definition: config.h:558
#define BRAKE_MODE_DECEL_RATE
Definition: config.h:561
uint64_t micros64()
void set_accel_z(float accel_cmss)
Definition: defines.h:97
void send_text(MAV_SEVERITY severity, const char *fmt,...)
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
float length(void) const
bool throw_position_good()
Definition: mode_throw.cpp:273
struct nav_filter_status::@138 flags
void run() override
Definition: mode_throw.cpp:27
AP_Int8 throw_motor_start
Definition: Parameters.h:459
uint32_t last_log_ms
Definition: Copter.h:1142
void set_alt_target(float alt_cm)
static struct notify_flags_and_values_type flags
MOTOR_CLASS *& motors
Definition: Copter.h:124
AP_HAL_MAIN_CALLBACKS & copter
Definition: ArduCopter.cpp:581
float & G_Dt
Definition: Copter.h:129
ThrowModeStage stage
Definition: Copter.h:1140
AP_Int8 throw_nextmode
Definition: Parameters.h:517
bool throw_attitude_good()
Definition: mode_throw.cpp:260
float & ekfNavVelGainScaler
Definition: Copter.h:137
AP_InertialNav & inertial_nav
Definition: Copter.h:121
virtual const Vector3f & get_velocity() const=0
AP_Int8 throw_type
Definition: Parameters.h:518
AP_AHRS & ahrs
Definition: Copter.h:122
virtual float get_altitude() const=0
int32_t get_pitch() const
Parameters & g
Definition: Copter.h:116
int32_t get_roll() const
float & ekfGndSpdLimit
Definition: Copter.h:134
bool nextmode_attempted
Definition: Copter.h:1143
float free_fall_start_velz
Definition: Copter.h:1145
Definition: defines.h:98
AC_Loiter *& loiter_nav
Definition: Copter.h:119
bool init(bool ignore_checks) override
Definition: mode_throw.cpp:6