APM:Copter
toy_mode.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 #if TOY_MODE_ENABLED == ENABLED
4 
5 // times in 0.1s units
6 #define TOY_COMMAND_DELAY 15
7 #define TOY_LONG_PRESS_COUNT 15
8 #define TOY_LAND_MANUAL_DISARM_COUNT 40
9 #define TOY_LAND_DISARM_COUNT 1
10 #define TOY_LAND_ARM_COUNT 1
11 #define TOY_RIGHT_PRESS_COUNT 1
12 #define TOY_ACTION_DELAY_MS 200
13 #define TOY_DESCENT_SLOW_HEIGHT 5
14 #define TOY_DESCENT_SLOW_RAMP 3
15 #define TOY_DESCENT_SLOW_MIN 300
16 #define TOY_RESET_TURTLE_TIME 5000
17 
18 #define ENABLE_LOAD_TEST 0
19 
21 
22  // @Param: _ENABLE
23  // @DisplayName: tmode enable
24  // @Description: tmode (or "toy" mode) gives a simplified user interface designed for mass market drones. Version1 is for the SkyViper V2450GPS. Version2 is for the F412 based boards
25  // @Values: 0:Disabled,1:EnableVersion1,2:EnableVersion2
26  // @User: Advanced
27  AP_GROUPINFO_FLAGS("_ENABLE", 1, ToyMode, enable, 0, AP_PARAM_FLAG_ENABLE),
28 
29  // @Param: _MODE1
30  // @DisplayName: Tmode first mode
31  // @Description: This is the initial mode when the vehicle is first turned on. This mode is assumed to not require GPS
32  // @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:FlowHold
33  // @User: Standard
34  AP_GROUPINFO("_MODE1", 2, ToyMode, primary_mode[0], ALT_HOLD),
35 
36  // @Param: _MODE2
37  // @DisplayName: Tmode second mode
38  // @Description: This is the secondary mode. This mode is assumed to require GPS
39  // @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:FlowHold
40  // @User: Standard
41  AP_GROUPINFO("_MODE2", 3, ToyMode, primary_mode[1], LOITER),
42 
43  // @Param: _ACTION1
44  // @DisplayName: Tmode action 1
45  // @Description: This is the action taken for the left action button
46  // @Values: 0:None,1:TakePhoto,2:ToggleVideo,3:ModeAcro,4:ModeAltHold,5:ModeAuto,6:ModeLoiter,7:ModeRTL,8:ModeCircle,9:ModeLand,10:ModeDrift,11:ModeSport,12:ModeAutoTune,13:ModePosHold,14:ModeBrake,15:ModeThrow,16:Flip,17:ModeStabilize,18:Disarm,19:ToggleMode,20:Arm-Land-RTL,21:ToggleSimpleMode,22:ToggleSuperSimpleMode,23:MotorLoadTest,24:ModeFlowHold
47  // @User: Standard
48  AP_GROUPINFO("_ACTION1", 4, ToyMode, actions[0], ACTION_TOGGLE_VIDEO),
49 
50  // @Param: _ACTION2
51  // @DisplayName: Tmode action 2
52  // @Description: This is the action taken for the right action button
53  // @Values: 0:None,1:TakePhoto,2:ToggleVideo,3:ModeAcro,4:ModeAltHold,5:ModeAuto,6:ModeLoiter,7:ModeRTL,8:ModeCircle,9:ModeLand,10:ModeDrift,11:ModeSport,12:ModeAutoTune,13:ModePosHold,14:ModeBrake,15:ModeThrow,16:Flip,17:ModeStabilize,18:Disarm,19:ToggleMode,20:Arm-Land-RTL,21:ToggleSimpleMode,22:ToggleSuperSimpleMode,23:MotorLoadTest,24:ModeFlowHold
54  // @User: Standard
55  AP_GROUPINFO("_ACTION2", 5, ToyMode, actions[1], ACTION_TAKE_PHOTO),
56 
57  // @Param: _ACTION3
58  // @DisplayName: Tmode action 3
59  // @Description: This is the action taken for the power button
60  // @Values: 0:None,1:TakePhoto,2:ToggleVideo,3:ModeAcro,4:ModeAltHold,5:ModeAuto,6:ModeLoiter,7:ModeRTL,8:ModeCircle,9:ModeLand,10:ModeDrift,11:ModeSport,12:ModeAutoTune,13:ModePosHold,14:ModeBrake,15:ModeThrow,16:Flip,17:ModeStabilize,18:Disarm,19:ToggleMode,20:Arm-Land-RTL,21:ToggleSimpleMode,22:ToggleSuperSimpleMode,23:MotorLoadTest,24:ModeFlowHold
61  // @User: Standard
62  AP_GROUPINFO("_ACTION3", 6, ToyMode, actions[2], ACTION_DISARM),
63 
64  // @Param: _ACTION4
65  // @DisplayName: Tmode action 4
66  // @Description: This is the action taken for the left action button while the mode button is pressed
67  // @Values: 0:None,1:TakePhoto,2:ToggleVideo,3:ModeAcro,4:ModeAltHold,5:ModeAuto,6:ModeLoiter,7:ModeRTL,8:ModeCircle,9:ModeLand,10:ModeDrift,11:ModeSport,12:ModeAutoTune,13:ModePosHold,14:ModeBrake,15:ModeThrow,16:Flip,17:ModeStabilize,18:Disarm,19:ToggleMode,20:Arm-Land-RTL,21:ToggleSimpleMode,22:ToggleSuperSimpleMode,23:MotorLoadTest,24:ModeFlowHold
68  // @User: Standard
69  AP_GROUPINFO("_ACTION4", 7, ToyMode, actions[3], ACTION_NONE),
70 
71  // @Param: _ACTION5
72  // @DisplayName: Tmode action 5
73  // @Description: This is the action taken for the right action button while the mode button is pressed
74  // @Values: 0:None,1:TakePhoto,2:ToggleVideo,3:ModeAcro,4:ModeAltHold,5:ModeAuto,6:ModeLoiter,7:ModeRTL,8:ModeCircle,9:ModeLand,10:ModeDrift,11:ModeSport,12:ModeAutoTune,13:ModePosHold,14:ModeBrake,15:ModeThrow,16:Flip,17:ModeStabilize,18:Disarm,19:ToggleMode,20:Arm-Land-RTL,21:ToggleSimpleMode,22:ToggleSuperSimpleMode,23:MotorLoadTest,24:ModeFlowHold
75  // @User: Standard
76  AP_GROUPINFO("_ACTION5", 8, ToyMode, actions[4], ACTION_NONE),
77 
78  // @Param: _ACTION6
79  // @DisplayName: Tmode action 6
80  // @Description: This is the action taken for the power button while the mode button is pressed
81  // @Values: 0:None,1:TakePhoto,2:ToggleVideo,3:ModeAcro,4:ModeAltHold,5:ModeAuto,6:ModeLoiter,7:ModeRTL,8:ModeCircle,9:ModeLand,10:ModeDrift,11:ModeSport,12:ModeAutoTune,13:ModePosHold,14:ModeBrake,15:ModeThrow,16:Flip,17:ModeStabilize,18:Disarm,19:ToggleMode,20:Arm-Land-RTL,21:ToggleSimpleMode,22:ToggleSuperSimpleMode,23:MotorLoadTest,24:ModeFlowHold
82  // @User: Standard
83  AP_GROUPINFO("_ACTION6", 9, ToyMode, actions[5], ACTION_NONE),
84 
85  // @Param: _LEFT
86  // @DisplayName: Tmode left action
87  // @Description: This is the action taken for the left button (mode button) being pressed
88  // @Values: 0:None,1:TakePhoto,2:ToggleVideo,3:ModeAcro,4:ModeAltHold,5:ModeAuto,6:ModeLoiter,7:ModeRTL,8:ModeCircle,9:ModeLand,10:ModeDrift,11:ModeSport,12:ModeAutoTune,13:ModePosHold,14:ModeBrake,15:ModeThrow,16:Flip,17:ModeStabilize,18:Disarm,19:ToggleMode,20:Arm-Land-RTL,21:ToggleSimpleMode,22:ToggleSuperSimpleMode,23:MotorLoadTest,24:ModeFlowHold
89  // @User: Standard
90  AP_GROUPINFO("_LEFT", 10, ToyMode, actions[6], ACTION_TOGGLE_MODE),
91 
92  // @Param: _LEFT_LONG
93  // @DisplayName: Tmode left long action
94  // @Description: This is the action taken for a long press of the left button (home button)
95  // @Values: 0:None,1:TakePhoto,2:ToggleVideo,3:ModeAcro,4:ModeAltHold,5:ModeAuto,6:ModeLoiter,7:ModeRTL,8:ModeCircle,9:ModeLand,10:ModeDrift,11:ModeSport,12:ModeAutoTune,13:ModePosHold,14:ModeBrake,15:ModeThrow,16:Flip,17:ModeStabilize,18:Disarm,19:ToggleMode,20:Arm-Land-RTL,21:ToggleSimpleMode,22:ToggleSuperSimpleMode,23:MotorLoadTest,24:ModeFlowHold
96  // @User: Standard
97  AP_GROUPINFO("_LEFT_LONG", 11, ToyMode, actions[7], ACTION_NONE),
98 
99  // @Param: _TRIM_AUTO
100  // @DisplayName: Stick auto trim limit
101  // @Description: This is the amount of automatic stick trim that can be applied when disarmed with sticks not moving. It is a PWM limit value away from 1500
102  // @Range: 0 100
103  // @User: Standard
104  AP_GROUPINFO("_TRIM_AUTO", 12, ToyMode, trim_auto, 50),
105 
106  // @Param: _RIGHT
107  // @DisplayName: Tmode right action
108  // @Description: This is the action taken for the right button (RTL) being pressed
109  // @Values: 0:None,1:TakePhoto,2:ToggleVideo,3:ModeAcro,4:ModeAltHold,5:ModeAuto,6:ModeLoiter,7:ModeRTL,8:ModeCircle,9:ModeLand,10:ModeDrift,11:ModeSport,12:ModeAutoTune,13:ModePosHold,14:ModeBrake,15:ModeThrow,16:Flip,17:ModeStabilize,18:Disarm,19:ToggleMode,20:Arm-Land-RTL,21:ToggleSimpleMode,22:ToggleSuperSimpleMode,23:MotorLoadTest
110  // @User: Standard
111  AP_GROUPINFO("_RIGHT", 13, ToyMode, actions[8], ACTION_ARM_LAND_RTL),
112 
113  // @Param: _FLAGS
114  // @DisplayName: Tmode flags
115  // @Description: Bitmask of flags to change the behaviour of tmode. DisarmOnLowThrottle means to disarm if throttle is held down for 1 second when landed. ArmOnHighThrottle means to arm if throttle is above 80% for 1 second. UpgradeToLoiter means to allow takeoff in LOITER mode by switching to ALT_HOLD, then auto-upgrading to LOITER once GPS is available. RTLStickCancel means that on large stick inputs in RTL mode that LOITER mode is engaged
116  // @Bitmask: 0:DisarmOnLowThrottle,1:ArmOnHighThrottle,2:UpgradeToLoiter,3:RTLStickCancel
117  // @User: Standard
118  AP_GROUPINFO("_FLAGS", 14, ToyMode, flags, FLAG_THR_DISARM),
119 
120  // @Param: _VMIN
121  // @DisplayName: Min voltage for output limiting
122  // @Description: This is the battery voltage below which no output limiting is done
123  // @Range: 0 5
124  // @Increment: 0.01
125  // @User: Advanced
126  AP_GROUPINFO("_VMIN", 15, ToyMode, filter.volt_min, 3.5),
127 
128  // @Param: _VMAX
129  // @DisplayName: Max voltage for output limiting
130  // @Description: This is the battery voltage above which thrust min is used
131  // @Range: 0 5
132  // @Increment: 0.01
133  // @User: Advanced
134  AP_GROUPINFO("_VMAX", 16, ToyMode, filter.volt_max, 3.8),
135 
136  // @Param: _TMIN
137  // @DisplayName: Min thrust multiplier
138  // @Description: This sets the thrust multiplier when voltage is high
139  // @Range: 0 1
140  // @Increment: 0.01
141  // @User: Advanced
142  AP_GROUPINFO("_TMIN", 17, ToyMode, filter.thrust_min, 1.0),
143 
144  // @Param: _TMAX
145  // @DisplayName: Max thrust multiplier
146  // @Description: This sets the thrust multiplier when voltage is low
147  // @Range: 0 1
148  // @Increment: 0.01
149  // @User: Advanced
150  AP_GROUPINFO("_TMAX", 18, ToyMode, filter.thrust_max, 1.0),
151 
152 #if ENABLE_LOAD_TEST
153  // @Param: _LOAD_MUL
154  // @DisplayName: Load test multiplier
155  // @Description: This scales the load test output, as a value between 0 and 1
156  // @Range: 0 1
157  // @Increment: 0.01
158  // @User: Advanced
159  AP_GROUPINFO("_LOAD_MUL", 19, ToyMode, load_test.load_mul, 1.0),
160 
161  // @Param: _LOAD_FILT
162  // @DisplayName: Load test filter
163  // @Description: This filters the load test output. A value of 1 means no filter. 2 means values are repeated once. 3 means values are repeated 3 times, etc
164  // @Range: 0 100
165  // @User: Advanced
166  AP_GROUPINFO("_LOAD_FILT", 20, ToyMode, load_test.load_filter, 1),
167 
168  // @Param: _LOAD_TYPE
169  // @DisplayName: Load test type
170  // @Description: This sets the type of load test
171  // @Values: 0:ConstantThrust,1:LogReplay1,2:LogReplay2
172  // @User: Advanced
173  AP_GROUPINFO("_LOAD_TYPE", 21, ToyMode, load_test.load_type, LOAD_TYPE_LOG1),
174 #endif
175 
177 };
178 
180 {
182 }
183 
184 /*
185  special mode handling for toys
186  */
187 void ToyMode::update()
188 {
189  if (!enable) {
190  // not enabled
191  return;
192  }
193 
194 #if ENABLE_LOAD_TEST
195  if (!copter.motors->armed()) {
196  load_test.running = false;
197  }
198 #endif
199 
200  // keep filtered battery voltage for thrust limiting
201  filtered_voltage = 0.99 * filtered_voltage + 0.01 * copter.battery.voltage();
202 
203  // update LEDs
204  blink_update();
205 
206  if (!done_first_update) {
207  done_first_update = true;
209  copter.motors->set_thrust_compensation_callback(FUNCTOR_BIND_MEMBER(&ToyMode::thrust_limiting, void, float *, uint8_t));
210  }
211 
212  // check if we should auto-trim
213  if (trim_auto > 0) {
214  trim_update();
215  }
216 
217  // set ALT_HOLD as indoors for the EKF (disables GPS vertical velocity fusion)
218 #if 0
219  copter.ahrs.set_indoor_mode(copter.control_mode == ALT_HOLD || copter.control_mode == FLOWHOLD);
220 #endif
221 
222  bool left_button = false;
223  bool right_button = false;
224  bool left_action_button = false;
225  bool right_action_button = false;
226  bool power_button = false;
227  bool left_change = false;
228 
229  uint16_t ch5_in = RC_Channels::get_radio_in(CH_5);
230  uint16_t ch6_in = RC_Channels::get_radio_in(CH_6);
231  uint16_t ch7_in = RC_Channels::get_radio_in(CH_7);
232 
233  if (copter.failsafe.radio || ch5_in < 900) {
234  // failsafe handling is outside the scope of toy mode, it does
235  // normal failsafe actions, just setup a blink pattern
239  return;
240  }
241 
242  uint32_t now = AP_HAL::millis();
243 
244  if (is_v2450_buttons()) {
245  // V2450 button mapping from cypress radio. It maps the
246  // buttons onto channels 5, 6 and 7 in a complex way, with the
247  // left button latching
248  left_change = ((ch5_in > 1700 && last_ch5 <= 1700) || (ch5_in <= 1700 && last_ch5 > 1700));
249 
250  last_ch5 = ch5_in;
251 
252  // get buttons from channels
253  left_button = (ch5_in > 2050 || (ch5_in > 1050 && ch5_in < 1150));
254  right_button = (ch6_in > 1500);
255  uint8_t ch7_bits = (ch7_in>1000)?uint8_t((ch7_in-1000)/100):0;
256  left_action_button = (ch7_bits&1) != 0;
257  right_action_button = (ch7_bits&2) != 0;
258  power_button = (ch7_bits&4) != 0;
259  } else if (is_f412_buttons()) {
260  // F412 button setup for cc2500 radio. This maps the 6 buttons
261  // onto channels 5 and 6, with no latching
262  uint8_t ch5_bits = (ch5_in>1000)?uint8_t((ch5_in-1000)/100):0;
263  uint8_t ch6_bits = (ch6_in>1000)?uint8_t((ch6_in-1000)/100):0;
264  left_button = (ch5_bits & 4) != 0;
265  right_button = (ch5_bits & 2) != 0;
266  right_action_button = (ch6_bits & 1) != 0;
267  left_action_button = (ch6_bits & 2) != 0;
268  power_button = (ch6_bits & 4) != 0;
269  left_change = (left_button != last_left_button);
270  last_left_button = left_button;
271  }
272 
273  // decode action buttons into an action
274  uint8_t action_input = 0;
275  if (left_action_button) {
276  action_input = 1;
277  } else if (right_action_button) {
278  action_input = 2;
279  } else if (power_button) {
280  action_input = 3;
281  }
282 
283  if (action_input != 0 && left_button) {
284  // combined button actions
285  action_input += 3;
286  left_press_counter = 0;
287  } else if (left_button) {
289  } else {
290  left_press_counter = 0;
291  }
292 
293  bool reset_combination = left_action_button && right_action_button;
294  if (reset_combination && abs(copter.ahrs.roll_sensor) > 160) {
295  /*
296  if both shoulder buttons are pressed at the same time for 5
297  seconds while the vehicle is inverted then we send a
298  WIFIRESET message to the sonix to reset SSID and password
299  */
300  if (reset_turtle_start_ms == 0) {
301  reset_turtle_start_ms = now;
302  }
303  if (now - reset_turtle_start_ms > TOY_RESET_TURTLE_TIME) {
304  gcs().send_text(MAV_SEVERITY_INFO, "Tmode: WiFi reset");
306  send_named_int("WIFIRESET", 1);
307  }
308  } else {
310  }
311  if (reset_combination) {
312  // don't act on buttons when combination pressed
313  action_input = 0;
314  left_press_counter = 0;
315  }
316 
317  /*
318  work out commanded action, if any
319  */
320  enum toy_action action = action_input?toy_action(actions[action_input-1].get()):ACTION_NONE;
321 
322  // check for long left button press
323  if (action == ACTION_NONE && left_press_counter > TOY_LONG_PRESS_COUNT) {
324  left_press_counter = -TOY_COMMAND_DELAY;
325  action = toy_action(actions[7].get());
326  ignore_left_change = true;
327  }
328 
329  // cope with long left press triggering a left change
330  if (ignore_left_change && left_change) {
331  left_change = false;
332  ignore_left_change = false;
333  }
334 
335  if (is_v2450_buttons()) {
336  // check for left button latching change
337  if (action == ACTION_NONE && left_change) {
338  action = toy_action(actions[6].get());
339  }
340  } else if (is_f412_buttons()) {
341  if (action == ACTION_NONE && left_change && !left_button) {
342  // left release
343  action = toy_action(actions[6].get());
344  }
345 
346  }
347 
348  // check for right button
349  if (action == ACTION_NONE && right_button) {
351  if (right_press_counter >= TOY_RIGHT_PRESS_COUNT) {
352  action = toy_action(actions[8].get());
353  right_press_counter = -TOY_COMMAND_DELAY;
354  }
355  } else {
357  }
358 
359  /*
360  some actions shouldn't repeat too fast
361  */
362  switch (action) {
363  case ACTION_TOGGLE_VIDEO:
364  case ACTION_TOGGLE_MODE:
367  case ACTION_ARM_LAND_RTL:
368  case ACTION_LOAD_TEST:
369  case ACTION_MODE_FLOW:
370  if (last_action == action ||
371  now - last_action_ms < TOY_ACTION_DELAY_MS) {
372  // for the above actions, button must be released before
373  // it will activate again
374  last_action = action;
375  action = ACTION_NONE;
376  }
377  break;
378 
379  case ACTION_TAKE_PHOTO:
380  // allow photo continuous shooting
381  if (now - last_action_ms < TOY_ACTION_DELAY_MS) {
382  last_action = action;
383  action = ACTION_NONE;
384  }
385  break;
386 
387  default:
388  last_action = action;
389  break;
390  }
391 
392  if (action != ACTION_NONE) {
393  gcs().send_text(MAV_SEVERITY_INFO, "Tmode: action %u", action);
394  last_action_ms = now;
395  }
396 
397  // we use 150 for throttle_at_min to cope with varying stick throws
398  bool throttle_at_min =
399  copter.channel_throttle->get_control_in() < 150;
400 
401  // throttle threshold for throttle arming
402  bool throttle_near_max =
403  copter.channel_throttle->get_control_in() > 700;
404 
405  /*
406  disarm if throttle is low for 1 second when landed
407  */
408  if ((flags & FLAG_THR_DISARM) && throttle_at_min && copter.motors->armed() && copter.ap.land_complete) {
410  const uint8_t disarm_limit = copter.flightmode->has_manual_throttle()?TOY_LAND_MANUAL_DISARM_COUNT:TOY_LAND_DISARM_COUNT;
411  if (throttle_low_counter >= disarm_limit) {
412  gcs().send_text(MAV_SEVERITY_INFO, "Tmode: throttle disarm");
413  copter.init_disarm_motors();
414  }
415  } else {
417  }
418 
419  /*
420  arm if throttle is high for 1 second when landed
421  */
422  if ((flags & FLAG_THR_ARM) && throttle_near_max && !copter.motors->armed()) {
424  if (throttle_high_counter >= TOY_LAND_ARM_COUNT) {
425  gcs().send_text(MAV_SEVERITY_INFO, "Tmode: throttle arm");
427  if (!copter.init_arm_motors(true) && (flags & FLAG_UPGRADE_LOITER) && copter.control_mode == LOITER) {
428  /*
429  support auto-switching to ALT_HOLD, then upgrade to LOITER once GPS available
430  */
432  gcs().send_text(MAV_SEVERITY_INFO, "Tmode: ALT_HOLD update arm");
433 #if AC_FENCE == ENABLED
434  copter.fence.enable(false);
435 #endif
436  if (!copter.init_arm_motors(true)) {
437  // go back to LOITER
438  gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: ALT_HOLD arm failed");
440  } else {
441  upgrade_to_loiter = true;
442 #if 0
443  AP_Notify::flags.hybrid_loiter = true;
444 #endif
445  }
446  }
447  } else {
449  }
450  }
451  } else {
453  }
454 
455  if (upgrade_to_loiter) {
456  if (!copter.motors->armed() || copter.control_mode != ALT_HOLD) {
457  upgrade_to_loiter = false;
458 #if 0
459  AP_Notify::flags.hybrid_loiter = false;
460 #endif
461  } else if (copter.position_ok() && set_and_remember_mode(LOITER, MODE_REASON_TMODE)) {
462 #if AC_FENCE == ENABLED
463  copter.fence.enable(true);
464 #endif
465  gcs().send_text(MAV_SEVERITY_INFO, "Tmode: LOITER update");
466  }
467  }
468 
469  if (copter.control_mode == RTL && (flags & FLAG_RTL_CANCEL) && throttle_near_max) {
470  gcs().send_text(MAV_SEVERITY_INFO, "Tmode: RTL cancel");
472  }
473 
474  enum control_mode_t old_mode = copter.control_mode;
475  enum control_mode_t new_mode = old_mode;
476 
477  /*
478  implement actions
479  */
480  switch (action) {
481  case ACTION_NONE:
482  break;
483 
484  case ACTION_TAKE_PHOTO:
485  send_named_int("SNAPSHOT", 1);
486  break;
487 
488  case ACTION_TOGGLE_VIDEO:
489  send_named_int("VIDEOTOG", 1);
490  break;
491 
492  case ACTION_MODE_ACRO:
493 #if MODE_ACRO_ENABLED == ENABLED
494  new_mode = ACRO;
495 #else
496  gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: ACRO is disabled");
497 #endif
498  break;
499 
500  case ACTION_MODE_ALTHOLD:
501  new_mode = ALT_HOLD;
502  break;
503 
504  case ACTION_MODE_AUTO:
505  new_mode = AUTO;
506  break;
507 
508  case ACTION_MODE_LOITER:
509  new_mode = LOITER;
510  break;
511 
512  case ACTION_MODE_RTL:
513  new_mode = RTL;
514  break;
515 
516  case ACTION_MODE_CIRCLE:
517  new_mode = CIRCLE;
518  break;
519 
520  case ACTION_MODE_LAND:
521  new_mode = LAND;
522  break;
523 
524  case ACTION_MODE_DRIFT:
525  new_mode = DRIFT;
526  break;
527 
528  case ACTION_MODE_SPORT:
529  new_mode = SPORT;
530  break;
531 
533  new_mode = AUTOTUNE;
534  break;
535 
536  case ACTION_MODE_POSHOLD:
537  new_mode = POSHOLD;
538  break;
539 
540  case ACTION_MODE_BRAKE:
541  new_mode = BRAKE;
542  break;
543 
544  case ACTION_MODE_THROW:
545 #if MODE_THROW_ENABLED == ENABLED
546  new_mode = THROW;
547 #else
548  gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: THROW is disabled");
549 #endif
550  break;
551 
552  case ACTION_MODE_FLIP:
553  new_mode = FLIP;
554  break;
555 
556  case ACTION_MODE_STAB:
557  new_mode = STABILIZE;
558  break;
559 
560  case ACTION_MODE_FLOW:
561  // toggle flow hold
562  if (old_mode != FLOWHOLD) {
563  new_mode = FLOWHOLD;
564  } else {
565  new_mode = ALT_HOLD;
566  }
567  break;
568 
569  case ACTION_DISARM:
570  if (copter.motors->armed()) {
571  gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: Force disarm");
572  copter.init_disarm_motors();
573  }
574  break;
575 
576  case ACTION_TOGGLE_MODE:
578  new_mode = control_mode_t(primary_mode[last_mode_choice].get());
579  break;
580 
582  copter.set_simple_mode(copter.ap.simple_mode?0:1);
583  break;
584 
586  copter.set_simple_mode(copter.ap.simple_mode?0:2);
587  break;
588 
589  case ACTION_ARM_LAND_RTL:
590  if (!copter.motors->armed()) {
591  action_arm();
592  } else if (old_mode == RTL) {
593  // switch between RTL and LOITER when in GPS modes
594  new_mode = LOITER;
595  } else if (old_mode == LAND) {
596  if (last_set_mode == LAND || !copter.position_ok()) {
597  // this is a land that we asked for, or we don't have good positioning
598  new_mode = ALT_HOLD;
599  } else if (copter.landing_with_GPS()) {
600  new_mode = LOITER;
601  } else {
602  new_mode = ALT_HOLD;
603  }
604  } else if (copter.flightmode->requires_GPS()) {
605  // if we're in a GPS mode, then RTL
606  new_mode = RTL;
607  } else {
608  // if we're in a non-GPS mode, then LAND
609  new_mode = LAND;
610  }
611  break;
612 
613  case ACTION_LOAD_TEST:
614 #if ENABLE_LOAD_TEST
615  if (copter.motors->armed() && !load_test.running) {
616  break;
617  }
618  if (load_test.running) {
619  load_test.running = false;
620  gcs().send_text(MAV_SEVERITY_INFO, "Tmode: load_test off");
621  copter.init_disarm_motors();
622  copter.set_mode(ALT_HOLD, MODE_REASON_TMODE);
623  } else {
624  copter.set_mode(ALT_HOLD, MODE_REASON_TMODE);
625 #if AC_FENCE == ENABLED
626  copter.fence.enable(false);
627 #endif
628  if (copter.init_arm_motors(true)) {
629  load_test.running = true;
630  gcs().send_text(MAV_SEVERITY_INFO, "Tmode: load_test on");
631  } else {
632  gcs().send_text(MAV_SEVERITY_INFO, "Tmode: load_test failed");
633  }
634  }
635 #endif
636  break;
637  }
638 
639  if (!copter.motors->armed() && (copter.control_mode == LAND || copter.control_mode == RTL)) {
640  // revert back to last primary flight mode if disarmed after landing
641  new_mode = control_mode_t(primary_mode[last_mode_choice].get());
642  }
643 
644  if (new_mode != copter.control_mode) {
645  load_test.running = false;
646 #if AC_FENCE == ENABLED
647  copter.fence.enable(false);
648 #endif
650  gcs().send_text(MAV_SEVERITY_INFO, "Tmode: mode %s", copter.flightmode->name4());
651  // force fence on in all GPS flight modes
652 #if AC_FENCE == ENABLED
653  if (copter.flightmode->requires_GPS()) {
654  copter.fence.enable(true);
655  }
656 #endif
657  } else {
658  gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: %u FAILED", (unsigned)new_mode);
659  if (new_mode == RTL) {
660  // if we can't RTL then land
661  gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: LANDING");
663 #if AC_FENCE == ENABLED
664  if (copter.landing_with_GPS()) {
665  copter.fence.enable(true);
666  }
667 #endif
668  }
669  }
670  }
671 }
672 
673 
674 /*
675  set a mode, remembering what mode we set, and the previous mode we were in
676  */
678 {
679  if (copter.control_mode == mode) {
680  return true;
681  }
682  if (!copter.set_mode(mode, reason)) {
683  return false;
684  }
685  last_set_mode = mode;
686  return true;
687 }
688 
689 /*
690  automatic stick trimming. This works while disarmed by looking for
691  zero rc-input changes for 4 seconds, and assuming sticks are
692  centered. Trim is saved
693  */
694 void ToyMode::trim_update(void)
695 {
696  if (hal.util->get_soft_armed() || copter.failsafe.radio) {
697  // only when disarmed and with RC link
698  trim.start_ms = 0;
699  return;
700  }
701 
702  // get throttle mid from channel trim
703  uint16_t throttle_trim = copter.channel_throttle->get_radio_trim();
704  if (abs(throttle_trim - 1500) <= trim_auto) {
705  RC_Channel *ch = copter.channel_throttle;
706  uint16_t ch_min = ch->get_radio_min();
707  uint16_t ch_max = ch->get_radio_max();
708  // remember the throttle midpoint
709  int16_t new_value = 1000UL * (throttle_trim - ch_min) / (ch_max - ch_min);
710  if (new_value != throttle_mid) {
711  throttle_mid = new_value;
712  gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: thr mid %d\n",
713  throttle_mid);
714  }
715  }
716 
717  uint16_t chan[4];
718  if (RC_Channels::get_radio_in(chan, 4) != 4) {
719  trim.start_ms = 0;
720  return;
721  }
722 
723  const uint16_t noise_limit = 2;
724  for (uint8_t i=0; i<4; i++) {
725  if (abs(chan[i] - 1500) > trim_auto) {
726  // not within limit
727  trim.start_ms = 0;
728  return;
729  }
730  }
731 
732  uint32_t now = AP_HAL::millis();
733 
734  if (trim.start_ms == 0) {
735  // start timer
736  memcpy(trim.chan, chan, 4*sizeof(uint16_t));
737  trim.start_ms = now;
738  return;
739  }
740 
741 
742  for (uint8_t i=0; i<4; i++) {
743  if (abs(trim.chan[i] - chan[i]) > noise_limit) {
744  // detected stick movement
745  memcpy(trim.chan, chan, 4*sizeof(uint16_t));
746  trim.start_ms = now;
747  return;
748  }
749  }
750 
751  if (now - trim.start_ms < 4000) {
752  // not steady for long enough yet
753  return;
754  }
755 
756  // reset timer so we don't trigger too often
757  trim.start_ms = 0;
758 
759  uint8_t need_trim = 0;
760  for (uint8_t i=0; i<4; i++) {
762  if (ch && abs(chan[i] - ch->get_radio_trim()) > noise_limit) {
763  need_trim |= 1U<<i;
764  }
765  }
766  if (need_trim == 0) {
767  return;
768  }
769  for (uint8_t i=0; i<4; i++) {
770  if (need_trim & (1U<<i)) {
772  ch->set_and_save_radio_trim(chan[i]);
773  }
774  }
775 
776  gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: trim %u %u %u %u\n",
777  chan[0], chan[1], chan[2], chan[3]);
778 }
779 
780 /*
781  handle arming action
782  */
783 void ToyMode::action_arm(void)
784 {
785  bool needs_gps = copter.flightmode->requires_GPS();
786 
787  // don't arm if sticks aren't in deadzone, to prevent pot problems
788  // on TX causing flight control issues
789  bool sticks_centered =
790  copter.channel_roll->get_control_in() == 0 &&
791  copter.channel_pitch->get_control_in() == 0 &&
792  copter.channel_yaw->get_control_in() == 0;
793 
794  if (!sticks_centered) {
795  gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: sticks not centered\n");
796  return;
797  }
798 
800 
801  if (needs_gps && copter.arming.gps_checks(false)) {
802 #if AC_FENCE == ENABLED
803  // we want GPS and checks are passing, arm and enable fence
804  copter.fence.enable(true);
805 #endif
806  copter.init_arm_motors(false);
807  if (!copter.motors->armed()) {
809  gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: GPS arming failed");
810  } else {
811  gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: GPS armed motors");
812  }
813  } else if (needs_gps) {
814  // notify of arming fail
816  gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: GPS arming failed");
817  } else {
818 #if AC_FENCE == ENABLED
819  // non-GPS mode
820  copter.fence.enable(false);
821 #endif
822  copter.init_arm_motors(false);
823  if (!copter.motors->armed()) {
825  gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: non-GPS arming failed");
826  } else {
827  gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: non-GPS armed motors");
828  }
829  }
830 }
831 
832 /*
833  adjust throttle for throttle takeoff
834  This prevents sudden climbs when using throttle for arming
835 */
836 void ToyMode::throttle_adjust(float &throttle_control)
837 {
838  uint32_t now = AP_HAL::millis();
839  const uint32_t soft_start_ms = 5000;
840  const uint16_t throttle_start = 600 + copter.g.throttle_deadzone;
841  if (!copter.motors->armed() && (flags & FLAG_THR_ARM)) {
842  throttle_control = MIN(throttle_control, 500);
843  } else if (now - throttle_arm_ms < soft_start_ms) {
844  float p = (now - throttle_arm_ms) / float(soft_start_ms);
845  throttle_control = MIN(throttle_control, throttle_start + p * (1000 - throttle_start));
846  }
847 
848  // limit descent rate close to the ground
849  float height = copter.inertial_nav.get_altitude() * 0.01 - copter.arming_altitude_m;
850  if (throttle_control < 500 &&
851  height < TOY_DESCENT_SLOW_HEIGHT + TOY_DESCENT_SLOW_RAMP &&
852  copter.motors->armed() && !copter.ap.land_complete) {
853  float limit = linear_interpolate(TOY_DESCENT_SLOW_MIN, 0, height,
854  TOY_DESCENT_SLOW_HEIGHT, TOY_DESCENT_SLOW_HEIGHT+TOY_DESCENT_SLOW_RAMP);
855  if (throttle_control < limit) {
856  // limit descent rate close to the ground
857  throttle_control = limit;
858  }
859  }
860 }
861 
862 
863 /*
864  update blinking. Blinking is done with a 16 bit pattern for each
865  LED. A count can be set for a pattern, which makes the pattern
866  persist until the count is zero. When it is zero the normal pattern
867  settings based on system status are used
868  */
869 void ToyMode::blink_update(void)
870 {
871  if (red_blink_pattern & (1U<<red_blink_index)) {
872  copter.relay.on(1);
873  } else {
874  copter.relay.off(1);
875  }
877  copter.relay.on(0);
878  } else {
879  copter.relay.off(0);
880  }
882  red_blink_index = (red_blink_index+1) % 16;
883  if (green_blink_index == 0 && green_blink_count > 0) {
885  }
886  if (red_blink_index == 0 && red_blink_count > 0) {
887  red_blink_count--;
888  }
889 
890  // let the TX know we are recording video
891  uint32_t now = AP_HAL::millis();
892  if (now - last_video_ms < 1000) {
894  } else {
896  }
897 
898  if (red_blink_count > 0 && green_blink_count > 0) {
899  return;
900  }
901 
902  // setup normal patterns based on flight mode and arming
903  uint16_t pattern = 0;
904 
905  // full on when we can see the TX, except for battery failsafe,
906  // when we blink rapidly
907  if (copter.motors->armed() && AP_Notify::flags.failsafe_battery) {
908  pattern = BLINK_8;
909  } else if (!copter.motors->armed() && (blink_disarm > 0)) {
910  pattern = BLINK_8;
911  blink_disarm--;
912  } else {
913  pattern = BLINK_FULL;
914  }
915 
916  if (copter.motors->armed()) {
917  blink_disarm = 4;
918  }
919 
920  if (red_blink_count == 0) {
921  red_blink_pattern = pattern;
922  }
923  if (green_blink_count == 0) {
924  green_blink_pattern = pattern;
925  }
926  if (red_blink_count == 0 && green_blink_count == 0) {
927  // get LEDs in sync
929  }
930 }
931 
932 // handle a mavlink message
933 void ToyMode::handle_message(mavlink_message_t *msg)
934 {
935  if (msg->msgid != MAVLINK_MSG_ID_NAMED_VALUE_INT) {
936  return;
937  }
938  mavlink_named_value_int_t m;
939  mavlink_msg_named_value_int_decode(msg, &m);
940  if (strncmp(m.name, "BLINKR", 10) == 0) {
941  red_blink_pattern = (uint16_t)m.value;
942  red_blink_count = m.value >> 16;
943  red_blink_index = 0;
944  } else if (strncmp(m.name, "BLINKG", 10) == 0) {
945  green_blink_pattern = (uint16_t)m.value;
946  green_blink_count = m.value >> 16;
947  green_blink_index = 0;
948  } else if (strncmp(m.name, "VNOTIFY", 10) == 0) {
949  // taking photos or video
950  if (green_blink_pattern != BLINK_2) {
951  green_blink_index = 0;
952  }
954  green_blink_count = 1;
956  // immediately update AP_Notify recording flag
958  } else if (strncmp(m.name, "WIFICHAN", 10) == 0) {
959 #if HAL_RCINPUT_WITH_AP_RADIO
960  AP_Radio *radio = AP_Radio::instance();
961  if (radio) {
962  radio->set_wifi_channel(m.value);
963  }
964 #endif
965  } else if (strncmp(m.name, "LOGDISARM", 10) == 0) {
966  enum ap_var_type vtype;
967  AP_Int8 *log_disarmed = (AP_Int8 *)AP_Param::find("LOG_DISARMED", &vtype);
968  if (log_disarmed) {
969  log_disarmed->set(int8_t(m.value));
970  }
971  }
972 }
973 
974 /*
975  send a named int to primary telem channel
976  */
977 void ToyMode::send_named_int(const char *name, int32_t value)
978 {
979  mavlink_msg_named_value_int_send(MAVLINK_COMM_1, AP_HAL::millis(), name, value);
980 }
981 
982 /*
983  limit maximum thrust based on voltage
984  */
985 void ToyMode::thrust_limiting(float *thrust, uint8_t num_motors)
986 {
987  float thrust_mul = linear_interpolate(filter.thrust_max, filter.thrust_min, filtered_voltage, filter.volt_min, filter.volt_max);
988  for (uint8_t i=0; i<num_motors; i++) {
989  thrust[i] *= thrust_mul;
990  }
991  uint16_t pwm[4];
992  hal.rcout->read(pwm, 4);
993  if (motor_log_counter++ % 10 == 0) {
994  DataFlash_Class::instance()->Log_Write("THST", "TimeUS,Vol,Mul,M1,M2,M3,M4", "QffHHHH",
996  (double)filtered_voltage,
997  (double)thrust_mul,
998  pwm[0], pwm[1], pwm[2], pwm[3]);
999  }
1000 
1001 }
1002 
1003 #if ENABLE_LOAD_TEST
1004 /*
1005  run a motor load test - used for endurance checking in factory tests
1006  */
1007 void ToyMode::load_test_run(void)
1008 {
1009  uint16_t pwm[4] {};
1010  switch ((enum load_type)load_test.load_type.get()) {
1011  case LOAD_TYPE_LOG1:
1012  for (uint8_t i=0; i<4; i++) {
1013  pwm[i] = load_data1[load_test.row].m[i];
1014  }
1015  load_test.filter_counter++;
1016  if (load_test.filter_counter >= load_test.load_filter.get()) {
1017  load_test.filter_counter = 0;
1018  load_test.row = (load_test.row + 1) % ARRAY_SIZE(load_data1);
1019  }
1020  break;
1021 
1022  case LOAD_TYPE_LOG2:
1023  // like log1, but all the same
1024  for (uint8_t i=0; i<4; i++) {
1025  pwm[i] = load_data1[load_test.row].m[0];
1026  }
1027  load_test.filter_counter++;
1028  if (load_test.filter_counter >= load_test.load_filter.get()) {
1029  load_test.filter_counter = 0;
1030  load_test.row = (load_test.row + 1) % ARRAY_SIZE(load_data1);
1031  }
1032  break;
1033 
1034  case LOAD_TYPE_CONSTANT:
1035  for (uint8_t i=0; i<4; i++) {
1036  pwm[i] = 500;
1037  }
1038  break;
1039  default:
1040  return;
1041  }
1042  for (uint8_t i=0; i<4; i++) {
1043  pwm[i] *= load_test.load_mul;
1044  // write, with conversion to 1000 to 2000 range
1045  hal.rcout->write(i, 1000 + pwm[i]*2);
1046  }
1047 
1048  if (copter.failsafe.battery) {
1049  gcs().send_text(MAV_SEVERITY_INFO, "Tmode: load_test off (battery)");
1050  copter.init_disarm_motors();
1051  load_test.running = false;
1052  }
1053 }
1054 #endif // ENABLE_LOAD_TEST
1055 
1056 /*
1057  if we try to arm and the compass is out of range then we enable
1058  inflight compass learning
1059  */
1060 void ToyMode::arm_check_compass(void)
1061 {
1062  // check for unreasonable compass offsets
1063  Vector3f offsets = copter.compass.get_offsets();
1064  float field = copter.compass.get_field().length();
1065 
1066  if (offsets.length() > copter.compass.get_offsets_max() ||
1067  field < 200 || field > 800 ||
1068  !copter.compass.configured()) {
1069  if (copter.compass.get_learn_type() != Compass::LEARN_INFLIGHT) {
1070  gcs().send_text(MAV_SEVERITY_INFO, "Tmode: enable compass learning");
1071  copter.compass.set_learn_type(Compass::LEARN_INFLIGHT, false);
1072  }
1073  }
1074 }
1075 
1076 #endif // TOY_MODE_ENABLED
bool get_soft_armed() const
int32_t right_press_counter
Definition: toy_mode.h:126
int16_t get_radio_trim() const
control_mode_t
Definition: defines.h:91
ap_var_type
virtual uint16_t read(uint8_t ch)=0
void trim_update(void)
float filtered_voltage
Definition: toy_mode.h:154
static RC_Channel * rc_channel(uint8_t chan)
int32_t left_press_counter
Definition: toy_mode.h:125
uint32_t last_video_ms
Definition: toy_mode.h:135
uint32_t throttle_low_counter
Definition: toy_mode.h:120
void thrust_limiting(float *thrust, uint8_t num_motors)
#define AP_GROUPINFO(name, idx, clazz, element, def)
uint32_t throttle_high_counter
Definition: toy_mode.h:121
Definition: defines.h:95
Definition: defines.h:106
static AP_Param * find(const char *name, enum ap_var_type *ptype)
AP_HAL::Util * util
Definition: defines.h:100
AP_Int8 enable
Definition: toy_mode.h:108
uint16_t green_blink_pattern
Definition: toy_mode.h:139
GCS & gcs()
void handle_message(mavlink_message_t *msg)
Definition: defines.h:101
Definition: defines.h:102
int16_t throttle_mid
Definition: toy_mode.h:128
mode_reason_t
Definition: defines.h:115
void blink_update(void)
uint32_t throttle_arm_ms
Definition: toy_mode.h:129
void arm_check_compass(void)
#define MIN(a, b)
AP_Int16 flags
Definition: toy_mode.h:112
control_mode_t last_set_mode
Definition: toy_mode.h:159
struct ToyMode::@19 filter
uint32_t reset_turtle_start_ms
Definition: toy_mode.h:132
void set_and_save_radio_trim(int16_t val)
static AP_Radio * instance(void)
#define AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, flags)
void send_named_int(const char *name, int32_t value)
float linear_interpolate(float low_output, float high_output, float var_value, float var_low, float var_high)
bool done_first_update
Definition: toy_mode.h:107
uint32_t last_action_ms
Definition: toy_mode.h:131
Definition: defines.h:93
void Log_Write(const char *name, const char *labels, const char *fmt,...)
uint16_t green_blink_count
Definition: toy_mode.h:143
void update(void)
bool ignore_left_change
Definition: toy_mode.h:127
uint8_t green_blink_index
Definition: toy_mode.h:141
const AP_HAL::HAL & hal
Definition: Copter.cpp:21
Definition: defines.h:103
uint32_t millis()
static const struct AP_Param::GroupInfo var_info[]
Definition: toy_mode.h:33
static DataFlash_Class * instance(void)
uint64_t micros64()
uint8_t blink_disarm
Definition: toy_mode.h:144
void set_wifi_channel(uint8_t channel)
Definition: defines.h:99
const char * name
Definition: defines.h:97
virtual void write(uint8_t ch, uint16_t period_us)=0
Definition: defines.h:107
toy_action
Definition: toy_mode.h:54
void send_text(MAV_SEVERITY severity, const char *fmt,...)
uint8_t motor_log_counter
Definition: toy_mode.h:156
#define ARRAY_SIZE(_arr)
AP_Int8 actions[9]
Definition: toy_mode.h:110
struct ToyMode::@20 load_test
bool last_left_button
Definition: toy_mode.h:123
float length(void) const
AP_Int8 load_filter
Definition: toy_mode.h:176
void throttle_adjust(float &throttle_control)
bool is_v2450_buttons(void) const
Definition: toy_mode.h:47
void NOINLINE filter(float &dst, float val, const byte k)
AP_Int8 trim_auto
Definition: toy_mode.h:111
uint8_t red_blink_index
Definition: toy_mode.h:140
static struct notify_flags_and_values_type flags
AP_HAL_MAIN_CALLBACKS & copter
Definition: ArduCopter.cpp:581
int16_t get_radio_min() const
int16_t get_radio_max() const
void load_test_run(void)
AP_Int8 primary_mode[2]
Definition: toy_mode.h:109
void action_arm(void)
static uint16_t get_radio_in(const uint8_t chan)
AP_HAL::RCOutput * rcout
uint16_t m[4]
Definition: toy_mode.h:162
bool upgrade_to_loiter
Definition: toy_mode.h:130
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
uint16_t last_ch5
Definition: toy_mode.h:122
static const struct load_data load_data1[]
Definition: toy_mode.h:180
uint16_t chan[4]
Definition: toy_mode.h:116
static struct notify_events_type events
#define AP_GROUPEND
uint8_t last_mode_choice
Definition: toy_mode.h:124
AP_Float load_mul
Definition: toy_mode.h:175
bool is_f412_buttons(void) const
Definition: toy_mode.h:50
Definition: defines.h:98
enum toy_action last_action
Definition: toy_mode.h:82
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
uint16_t red_blink_count
Definition: toy_mode.h:142
struct ToyMode::@18 trim
bool set_and_remember_mode(control_mode_t mode, mode_reason_t reason)
uint16_t red_blink_pattern
Definition: toy_mode.h:138