APM:Copter
motors.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 #define ARM_DELAY 20 // called at 10hz so 2 seconds
4 #define DISARM_DELAY 20 // called at 10hz so 2 seconds
5 #define AUTO_TRIM_DELAY 100 // called at 10hz so 10 seconds
6 #define LOST_VEHICLE_DELAY 10 // called at 10hz so 1 second
7 
8 static uint32_t auto_disarm_begin;
9 
10 // arm_motors_check - checks for pilot input to arm or disarm the copter
11 // called at 10hz
13 {
14  static int16_t arming_counter;
15 
16 #if TOY_MODE_ENABLED == ENABLED
17  if (g2.toy_mode.enabled()) {
18  // not armed with sticks in toy mode
19  return;
20  }
21 #endif
22 
23  // ensure throttle is down
24  if (channel_throttle->get_control_in() > 0) {
25  arming_counter = 0;
26  return;
27  }
28 
29  int16_t tmp = channel_yaw->get_control_in();
30 
31  // full right
32  if (tmp > 4000) {
33 
34  // increase the arming counter to a maximum of 1 beyond the auto trim counter
35  if( arming_counter <= AUTO_TRIM_DELAY ) {
36  arming_counter++;
37  }
38 
39  // arm the motors and configure for flight
40  if (arming_counter == ARM_DELAY && !motors->armed()) {
41  // reset arming counter if arming fail
42  if (!init_arm_motors(false)) {
43  arming_counter = 0;
44  }
45  }
46 
47  // arm the motors and configure for flight
48  if (arming_counter == AUTO_TRIM_DELAY && motors->armed() && control_mode == STABILIZE) {
49  auto_trim_counter = 250;
50  // ensure auto-disarm doesn't trigger immediately
52  }
53 
54  // full left
55  }else if (tmp < -4000) {
56  if (!flightmode->has_manual_throttle() && !ap.land_complete) {
57  arming_counter = 0;
58  return;
59  }
60 
61  // increase the counter to a maximum of 1 beyond the disarm delay
62  if( arming_counter <= DISARM_DELAY ) {
63  arming_counter++;
64  }
65 
66  // disarm the motors
67  if (arming_counter == DISARM_DELAY && motors->armed()) {
69  }
70 
71  // Yaw is centered so reset arming counter
72  }else{
73  arming_counter = 0;
74  }
75 }
76 
77 // auto_disarm_check - disarms the copter if it has been sitting on the ground in manual mode with throttle low for at least 15 seconds
79 {
80  uint32_t tnow_ms = millis();
81  uint32_t disarm_delay_ms = 1000*constrain_int16(g.disarm_delay, 0, 127);
82 
83  // exit immediately if we are already disarmed, or if auto
84  // disarming is disabled
85  if (!motors->armed() || disarm_delay_ms == 0 || control_mode == THROW) {
86  auto_disarm_begin = tnow_ms;
87  return;
88  }
89 
90 #if FRAME_CONFIG == HELI_FRAME
91  // if the rotor is still spinning, don't initiate auto disarm
92  if (motors->rotor_speed_above_critical()) {
93  auto_disarm_begin = tnow_ms;
94  return;
95  }
96 #endif
97 
98  // always allow auto disarm if using interlock switch or motors are Emergency Stopped
99  if ((ap.using_interlock && !motors->get_interlock()) || ap.motor_emergency_stop) {
100 #if FRAME_CONFIG != HELI_FRAME
101  // use a shorter delay if using throttle interlock switch or Emergency Stop, because it is less
102  // obvious the copter is armed as the motors will not be spinning
103  disarm_delay_ms /= 2;
104 #endif
105  } else {
106  bool sprung_throttle_stick = (g.throttle_behavior & THR_BEHAVE_FEEDBACK_FROM_MID_STICK) != 0;
107  bool thr_low;
108  if (flightmode->has_manual_throttle() || !sprung_throttle_stick) {
109  thr_low = ap.throttle_zero;
110  } else {
111  float deadband_top = get_throttle_mid() + g.throttle_deadzone;
112  thr_low = channel_throttle->get_control_in() <= deadband_top;
113  }
114 
115  if (!thr_low || !ap.land_complete) {
116  // reset timer
117  auto_disarm_begin = tnow_ms;
118  }
119  }
120 
121  // disarm once timer expires
122  if ((tnow_ms-auto_disarm_begin) >= disarm_delay_ms) {
124  auto_disarm_begin = tnow_ms;
125  }
126 }
127 
128 // init_arm_motors - performs arming process including initialisation of barometer and gyros
129 // returns false if arming failed because of pre-arm checks, arming checks or a gyro calibration failure
130 bool Copter::init_arm_motors(bool arming_from_gcs)
131 {
132  static bool in_arm_motors = false;
133 
134  // exit immediately if already in this function
135  if (in_arm_motors) {
136  return false;
137  }
138  in_arm_motors = true;
139 
140  // return true if already armed
141  if (motors->armed()) {
142  in_arm_motors = false;
143  return true;
144  }
145 
146  // run pre-arm-checks and display failures
147  if (!arming.all_checks_passing(arming_from_gcs)) {
149  in_arm_motors = false;
150  return false;
151  }
152 
153  // let dataflash know that we're armed (it may open logs e.g.)
155 
156  // disable cpu failsafe because initialising everything takes a while
158 
159  // notify that arming will occur (we do this early to give plenty of warning)
160  AP_Notify::flags.armed = true;
161  // call notify update a few times to ensure the message gets out
162  for (uint8_t i=0; i<=10; i++) {
163  notify.update();
164  }
165 
166 #if HIL_MODE != HIL_MODE_DISABLED || CONFIG_HAL_BOARD == HAL_BOARD_SITL
167  gcs().send_text(MAV_SEVERITY_INFO, "Arming motors");
168 #endif
169 
170  // Remember Orientation
171  // --------------------
173 
175 
176  if (!ahrs.home_is_set()) {
177  // Reset EKF altitude if home hasn't been set yet (we use EKF altitude as substitute for alt above home)
180 
181  // we have reset height, so arming height is zero
182  arming_altitude_m = 0;
183  } else if (!ahrs.home_is_locked()) {
184  // Reset home position if it has already been set before (but not locked)
186 
187  // remember the height when we armed
189  }
191 
192  // Reset SmartRTL return location. If activated, SmartRTL will ultimately try to land at this point
193 #if MODE_SMARTRTL_ENABLED == ENABLED
195 #endif
196 
197  // enable gps velocity based centrefugal force compensation
199  hal.util->set_soft_armed(true);
200 
201 #if SPRAYER == ENABLED
202  // turn off sprayer's test if on
203  sprayer.test_pump(false);
204 #endif
205 
206  // enable output to motors
208 
209  // finally actually arm the motors
210  motors->armed(true);
211 
212  // log arming to dataflash
214 
215  // log flight mode in case it was changed while vehicle was disarmed
217 
218  // reenable failsafe
219  failsafe_enable();
220 
221  // perf monitor ignores delay due to arming
223 
224  // flag exiting this function
225  in_arm_motors = false;
226 
227  // Log time stamp of arming event
228  arm_time_ms = millis();
229 
230  // Start the arming delay
231  ap.in_arming_delay = true;
232 
233  // assumed armed without a arming, switch. Overridden in switches.cpp
234  ap.armed_with_switch = false;
235 
236  // return success
237  return true;
238 }
239 
240 // init_disarm_motors - disarm motors
242 {
243  // return immediately if we are already disarmed
244  if (!motors->armed()) {
245  return;
246  }
247 
248 #if HIL_MODE != HIL_MODE_DISABLED || CONFIG_HAL_BOARD == HAL_BOARD_SITL
249  gcs().send_text(MAV_SEVERITY_INFO, "Disarming motors");
250 #endif
251 
252  // save compass offsets learned by the EKF if enabled
254  for(uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
255  Vector3f magOffsets;
256  if (ahrs.getMagOffsets(i, magOffsets)) {
257  compass.set_and_save_offsets(i, magOffsets);
258  }
259  }
260  }
261 
262 #if AUTOTUNE_ENABLED == ENABLED
263  // save auto tuned parameters
265 #endif
266 
267  // we are not in the air
268  set_land_complete(true);
270 
271  // log disarm to the dataflash
273 
274  // send disarm command to motors
275  motors->armed(false);
276 
277 #if MODE_AUTO_ENABLED == ENABLED
278  // reset the mission
279  mission.reset();
280 #endif
281 
283 
284  // disable gps velocity based centrefugal force compensation
286  hal.util->set_soft_armed(false);
287 
288  ap.in_arming_delay = false;
289 }
290 
291 // motors_output - send output to motors library which will adjust and send to ESCs and servos
293 {
294 #if ADVANCED_FAILSAFE == ENABLED
295  // this is to allow the failsafe module to deliberately crash
296  // the vehicle. Only used in extreme circumstances to meet the
297  // OBC rules
298  if (g2.afs.should_crash_vehicle()) {
300  return;
301  }
302 #endif
303 
304  // Update arming delay state
305  if (ap.in_arming_delay && (!motors->armed() || millis()-arm_time_ms > ARMING_DELAY_SEC*1.0e3f || control_mode == THROW)) {
306  ap.in_arming_delay = false;
307  }
308 
309  // output any servo channels
311 
312  // cork now, so that all channel outputs happen at once
314 
315  // update output on any aux channels, for manual passthru
317 
318  // check if we are performing the motor test
319  if (ap.motor_test) {
321  } else {
322  bool interlock = motors->armed() && !ap.in_arming_delay && (!ap.using_interlock || ap.motor_interlock_switch) && !ap.motor_emergency_stop;
323  if (!motors->get_interlock() && interlock) {
324  motors->set_interlock(true);
326  } else if (motors->get_interlock() && !interlock) {
327  motors->set_interlock(false);
329  }
330 
331  // send output signals to motors
332  motors->output();
333  }
334 
335  // push all channels
337 }
338 
339 // check for pilot stick input to trigger lost vehicle alarm
341 {
342  static uint8_t soundalarm_counter;
343 
344  // disable if aux switch is setup to vehicle alarm as the two could interfere
346  return;
347  }
348 
349  // ensure throttle is down, motors not armed, pitch and roll rc at max. Note: rc1=roll rc2=pitch
350  if (ap.throttle_zero && !motors->armed() && (channel_roll->get_control_in() > 4000) && (channel_pitch->get_control_in() > 4000)) {
351  if (soundalarm_counter >= LOST_VEHICLE_DELAY) {
352  if (AP_Notify::flags.vehicle_lost == false) {
354  gcs().send_text(MAV_SEVERITY_NOTICE,"Locate Copter alarm");
355  }
356  } else {
357  soundalarm_counter++;
358  }
359  } else {
360  soundalarm_counter = 0;
361  if (AP_Notify::flags.vehicle_lost == true) {
363  }
364  }
365 }
void test_pump(bool true_false)
#define AUTO_TRIM_DELAY
Definition: motors.cpp:5
bool use_compass() override
AP_AHRS_NavEKF ahrs
Definition: Copter.h:255
#define ARM_DELAY
Definition: motors.cpp:3
bool resetHeightDatum() override
void motors_output()
Definition: motors.cpp:292
float get_altitude() const
void auto_disarm_check()
Definition: motors.cpp:78
int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
AP_Arming_Copter arming
Definition: Copter.h:280
void set_land_complete_maybe(bool b)
AP_Int16 throttle_behavior
Definition: Parameters.h:387
void failsafe_disable()
Definition: failsafe.cpp:27
RC_Channel * channel_roll
Definition: Copter.h:221
ToyMode toy_mode
Definition: Parameters.h:586
bool all_checks_passing(bool arming_from_gcs)
Definition: AP_Arming.cpp:19
void Log_Write_Mode(uint8_t mode, uint8_t reason)
GCS_Copter & gcs()
Definition: Copter.h:301
void set_and_save_offsets(uint8_t i, const Vector3f &offsets)
bool getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const
AP_HAL::Util * util
void ignore_this_loop()
bool enabled(void) const
Definition: toy_mode.h:14
#define DATA_EKF_ALT_RESET
Definition: defines.h:380
#define DATA_ARMED
Definition: defines.h:339
static void push()
AP_InertialNav_NavEKF inertial_nav
Definition: Copter.h:483
void reset()
RC_Channel * channel_yaw
Definition: Copter.h:224
MOTOR_CLASS * motors
Definition: Copter.h:422
#define DATA_MOTORS_INTERLOCK_DISABLED
Definition: defines.h:376
#define DISARM_DELAY
Definition: motors.cpp:4
static void output_ch_all(void)
#define LOST_VEHICLE_DELAY
Definition: motors.cpp:6
bool init_arm_motors(bool arming_from_gcs)
Definition: motors.cpp:130
int16_t get_throttle_mid(void)
Definition: radio.cpp:203
mode_reason_t control_mode_reason
Definition: Copter.h:346
RC_Channel * channel_throttle
Definition: Copter.h:223
void set_vehicle_armed(bool armed_state)
bool check_if_auxsw_mode_used(uint8_t auxsw_mode_check)
Definition: switches.cpp:79
int16_t get_control_in() const
RC_Channel * channel_pitch
Definition: Copter.h:222
void motor_test_output()
Definition: motor_test.cpp:21
Mode * flightmode
Definition: Copter.h:955
void lost_vehicle_check()
Definition: motors.cpp:340
AP_Int8 disarm_delay
Definition: Parameters.h:450
const AP_HAL::HAL & hal
Definition: Copter.cpp:21
void Log_Write_Event(uint8_t id)
Definition: Log.cpp:200
#define DATA_DISARMED
Definition: defines.h:340
uint32_t millis()
AP_Notify notify
Definition: Copter.h:215
void set_correct_centrifugal(bool setting)
static DataFlash_Class * instance(void)
AP_AdvancedFailsafe_Copter afs
Definition: Parameters.h:547
void init_simple_bearing()
Definition: ArduCopter.cpp:485
AP_Int16 throttle_deadzone
Definition: Parameters.h:423
Definition: defines.h:107
void send_text(MAV_SEVERITY severity, const char *fmt,...)
#define ARMING_DELAY_SEC
Definition: config.h:52
void set_land_complete(bool b)
DataFlash_Class DataFlash
Definition: Copter.h:227
void update_super_simple_bearing(bool force_update)
Definition: ArduCopter.cpp:532
int32_t initial_armed_bearing
Definition: Copter.h:442
AP_Scheduler scheduler
Definition: Copter.h:212
enum LearnType get_learn_type(void) const
Parameters g
Definition: Copter.h:208
ModeAutoTune mode_autotune
Definition: Copter.h:968
#define COMPASS_MAX_INSTANCES
#define THR_BEHAVE_FEEDBACK_FROM_MID_STICK
Definition: defines.h:483
bool home_is_locked() const
void set_soft_armed(const bool b)
Compass compass
Definition: Copter.h:235
static struct notify_flags_and_values_type flags
bool set_home_to_current_location(bool lock)
Definition: commands.cpp:38
uint32_t arm_time_ms
Definition: Copter.h:503
AC_Sprayer sprayer
Definition: Copter.h:548
bool position_ok()
Definition: system.cpp:312
void init_disarm_motors()
Definition: motors.cpp:241
virtual bool has_manual_throttle() const =0
static void cork()
ParametersG2 g2
Definition: Copter.h:209
void update(void)
void set_home(bool position_ok)
#define DATA_MOTORS_INTERLOCK_ENABLED
Definition: defines.h:377
void arm_motors_check()
Definition: motors.cpp:12
float arming_altitude_m
Definition: Copter.h:378
bool should_crash_vehicle(void)
bool home_is_set(void) const
static struct notify_events_type events
static void calc_pwm(void)
int32_t yaw_sensor
control_mode_t control_mode
Definition: Copter.h:345
void enable_motor_output()
Definition: radio.cpp:88
static uint32_t auto_disarm_begin
Definition: motors.cpp:8
AP_Mission mission
Definition: Copter.h:263
AP_SmartRTL smart_rtl
Definition: Parameters.h:570
uint8_t auto_trim_counter
Definition: Copter.h:506
void failsafe_enable()
Definition: failsafe.cpp:18
AP::PerfInfo perf_info