APM:Copter
mode_auto.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 #if MODE_AUTO_ENABLED == ENABLED
4 
5 /*
6  * Init and run calls for auto flight mode
7  *
8  * This file contains the implementation for Land, Waypoint navigation and Takeoff from Auto mode
9  * Command execution code (i.e. command_logic.pde) should:
10  * a) switch to Auto flight mode with set_mode() function. This will cause auto_init to be called
11  * b) call one of the three auto initialisation functions: auto_wp_start(), auto_takeoff_start(), auto_land_start()
12  * c) call one of the verify functions auto_wp_verify(), auto_takeoff_verify, auto_land_verify repeated to check if the command has completed
13  * The main loop (i.e. fast loop) will call update_flight_modes() which will in turn call auto_run() which, based upon the auto_mode variable will call
14  * correct auto_wp_run, auto_takeoff_run or auto_land_run to actually implement the feature
15  */
16 
17 /*
18  * While in the auto flight mode, navigation or do/now commands can be run.
19  * Code in this file implements the navigation commands
20  */
21 
22 // auto_init - initialise auto controller
23 bool Copter::ModeAuto::init(bool ignore_checks)
24 {
25  if ((copter.position_ok() && copter.mission.num_commands() > 1) || ignore_checks) {
27 
28  // reject switching to auto mode if landed with motors armed but first command is not a takeoff (reduce chance of flips)
29  if (motors->armed() && ap.land_complete && !copter.mission.starts_with_takeoff_cmd()) {
30  gcs().send_text(MAV_SEVERITY_CRITICAL, "Auto: Missing Takeoff Cmd");
31  return false;
32  }
33 
34  // stop ROI from carrying over from previous runs of the mission
35  // To-Do: reset the yaw as part of auto_wp_start when the previous command was not a wp command to remove the need for this special ROI check
36  if (auto_yaw.mode() == AUTO_YAW_ROI) {
38  }
39 
40  // initialise waypoint and spline controller
42 
43  // clear guided limits
44  copter.mode_guided.limit_clear();
45 
46  // start/resume the mission (based on MIS_RESTART parameter)
47  copter.mission.start_or_resume();
48  return true;
49  } else {
50  return false;
51  }
52 }
53 
54 // auto_run - runs the auto controller
55 // should be called at 100hz or more
56 // relies on run_autopilot being called at 10hz which handles decision making and non-navigation related commands
58 {
59  // call the correct auto controller
60  switch (_mode) {
61 
62  case Auto_TakeOff:
63  takeoff_run();
64  break;
65 
66  case Auto_WP:
68  wp_run();
69  break;
70 
71  case Auto_Land:
72  land_run();
73  break;
74 
75  case Auto_RTL:
76  rtl_run();
77  break;
78 
79  case Auto_Circle:
80  circle_run();
81  break;
82 
83  case Auto_Spline:
84  spline_run();
85  break;
86 
87  case Auto_NavGuided:
88 #if NAV_GUIDED == ENABLED
90 #endif
91  break;
92 
93  case Auto_Loiter:
94  loiter_run();
95  break;
96 
99  break;
100  }
101 }
102 
103 // auto_loiter_start - initialises loitering in auto mode
104 // returns success/failure because this can be called by exit_mission
106 {
107  // return failure if GPS is bad
108  if (!copter.position_ok()) {
109  return false;
110  }
111  _mode = Auto_Loiter;
112 
113  // calculate stopping point
114  Vector3f stopping_point;
115  wp_nav->get_wp_stopping_point(stopping_point);
116 
117  // initialise waypoint controller target to stopping point
118  wp_nav->set_wp_destination(stopping_point);
119 
120  // hold yaw at current heading
122 
123  return true;
124 }
125 
126 // auto_rtl_start - initialises RTL in AUTO flight mode
128 {
129  _mode = Auto_RTL;
130 
131  // call regular rtl flight mode initialisation and ask it to ignore checks
132  copter.mode_rtl.init(true);
133 }
134 
135 // auto_takeoff_start - initialises waypoint controller to implement take-off
137 {
139 
140  // convert location to class
141  Location_Class dest(dest_loc);
142 
143  // set horizontal target
144  dest.lat = copter.current_loc.lat;
145  dest.lng = copter.current_loc.lng;
146 
147  // get altitude target
148  int32_t alt_target;
149  if (!dest.get_alt_cm(Location_Class::ALT_FRAME_ABOVE_HOME, alt_target)) {
150  // this failure could only happen if take-off alt was specified as an alt-above terrain and we have no terrain data
152  // fall back to altitude above current altitude
153  alt_target = copter.current_loc.alt + dest.alt;
154  }
155 
156  // sanity check target
157  if (alt_target < copter.current_loc.alt) {
159  }
160  // Note: if taking off from below home this could cause a climb to an unexpectedly high altitude
161  if (alt_target < 100) {
163  }
164 
165  // set waypoint controller target
166  if (!wp_nav->set_wp_destination(dest)) {
167  // failure to set destination can only be because of missing terrain data
168  copter.failsafe_terrain_on_event();
169  return;
170  }
171 
172  // initialise yaw
174 
175  // clear i term when we're taking off
177 
178  // get initial alt for WP_NAVALT_MIN
179  copter.auto_takeoff_set_start_alt();
180 }
181 
182 // auto_wp_start - initialises waypoint controller to implement flying to a particular destination
183 void Copter::ModeAuto::wp_start(const Vector3f& destination)
184 {
185  _mode = Auto_WP;
186 
187  // initialise wpnav (no need to check return status because terrain data is not used)
188  wp_nav->set_wp_destination(destination, false);
189 
190  // initialise yaw
191  // To-Do: reset the yaw only when the previous navigation command is not a WP. this would allow removing the special check for ROI
192  if (auto_yaw.mode() != AUTO_YAW_ROI) {
194  }
195 }
196 
197 // auto_wp_start - initialises waypoint controller to implement flying to a particular destination
199 {
200  _mode = Auto_WP;
201 
202  // send target to waypoint controller
203  if (!wp_nav->set_wp_destination(dest_loc)) {
204  // failure to set destination can only be because of missing terrain data
205  copter.failsafe_terrain_on_event();
206  return;
207  }
208 
209  // initialise yaw
210  // To-Do: reset the yaw only when the previous navigation command is not a WP. this would allow removing the special check for ROI
211  if (auto_yaw.mode() != AUTO_YAW_ROI) {
213  }
214 }
215 
216 // auto_land_start - initialises controller to implement a landing
218 {
219  // set target to stopping point
220  Vector3f stopping_point;
221  loiter_nav->get_stopping_point_xy(stopping_point);
222 
223  // call location specific land start function
224  land_start(stopping_point);
225 }
226 
227 // auto_land_start - initialises controller to implement a landing
228 void Copter::ModeAuto::land_start(const Vector3f& destination)
229 {
230  _mode = Auto_Land;
231 
232  // initialise loiter target destination
233  loiter_nav->init_target(destination);
234 
235  // initialise position and desired velocity
236  if (!pos_control->is_active_z()) {
239  }
240 
241  // initialise yaw
243 }
244 
245 // auto_circle_movetoedge_start - initialise waypoint controller to move to edge of a circle with it's center at the specified location
246 // we assume the caller has performed all required GPS_ok checks
247 void Copter::ModeAuto::circle_movetoedge_start(const Location_Class &circle_center, float radius_m)
248 {
249  // convert location to vector from ekf origin
250  Vector3f circle_center_neu;
251  if (!circle_center.get_vector_from_origin_NEU(circle_center_neu)) {
252  // default to current position and log error
253  circle_center_neu = inertial_nav.get_position();
255  }
256  copter.circle_nav->set_center(circle_center_neu);
257 
258  // set circle radius
259  if (!is_zero(radius_m)) {
260  copter.circle_nav->set_radius(radius_m * 100.0f);
261  }
262 
263  // check our distance from edge of circle
264  Vector3f circle_edge_neu;
265  copter.circle_nav->get_closest_point_on_circle(circle_edge_neu);
266  float dist_to_edge = (inertial_nav.get_position() - circle_edge_neu).length();
267 
268  // if more than 3m then fly to edge
269  if (dist_to_edge > 300.0f) {
270  // set the state to move to the edge of the circle
272 
273  // convert circle_edge_neu to Location_Class
274  Location_Class circle_edge(circle_edge_neu);
275 
276  // convert altitude to same as command
277  circle_edge.set_alt_cm(circle_center.alt, circle_center.get_alt_frame());
278 
279  // initialise wpnav to move to edge of circle
280  if (!wp_nav->set_wp_destination(circle_edge)) {
281  // failure to set destination can only be because of missing terrain data
282  copter.failsafe_terrain_on_event();
283  }
284 
285  // if we are outside the circle, point at the edge, otherwise hold yaw
286  const Vector3f &curr_pos = inertial_nav.get_position();
287  float dist_to_center = norm(circle_center_neu.x - curr_pos.x, circle_center_neu.y - curr_pos.y);
288  if (dist_to_center > copter.circle_nav->get_radius() && dist_to_center > 500) {
290  } else {
291  // vehicle is within circle so hold yaw to avoid spinning as we move to edge of circle
293  }
294  } else {
295  circle_start();
296  }
297 }
298 
299 // auto_circle_start - initialises controller to fly a circle in AUTO flight mode
300 // assumes that circle_nav object has already been initialised with circle center and radius
302 {
303  _mode = Auto_Circle;
304 
305  // initialise circle controller
306  copter.circle_nav->init(copter.circle_nav->get_center());
307 }
308 
309 // auto_spline_start - initialises waypoint controller to implement flying to a particular destination using the spline controller
310 // seg_end_type can be SEGMENT_END_STOP, SEGMENT_END_STRAIGHT or SEGMENT_END_SPLINE. If Straight or Spline the next_destination should be provided
311 void Copter::ModeAuto::spline_start(const Location_Class& destination, bool stopped_at_start,
312  AC_WPNav::spline_segment_end_type seg_end_type,
313  const Location_Class& next_destination)
314 {
315  _mode = Auto_Spline;
316 
317  // initialise wpnav
318  if (!wp_nav->set_spline_destination(destination, stopped_at_start, seg_end_type, next_destination)) {
319  // failure to set destination can only be because of missing terrain data
320  copter.failsafe_terrain_on_event();
321  return;
322  }
323 
324  // initialise yaw
325  // To-Do: reset the yaw only when the previous navigation command is not a WP. this would allow removing the special check for ROI
326  if (auto_yaw.mode() != AUTO_YAW_ROI) {
328  }
329 }
330 
331 #if NAV_GUIDED == ENABLED
332 // auto_nav_guided_start - hand over control to external navigation controller in AUTO mode
334 {
336 
337  // call regular guided flight mode initialisation
338  copter.mode_guided.init(true);
339 
340  // initialise guided start time and position as reference for limit checking
341  copter.mode_guided.limit_init_time_and_pos();
342 }
343 #endif //NAV_GUIDED
344 
346 {
347  switch(_mode) {
348  case Auto_Land:
349  return true;
350  case Auto_RTL:
351  return copter.mode_rtl.landing_gear_should_be_deployed();
352  default:
353  return false;
354  }
355  return false;
356 }
357 
358 // auto_payload_place_start - initialises controller to implement a placing
360 {
361  // set target to stopping point
362  Vector3f stopping_point;
363  loiter_nav->get_stopping_point_xy(stopping_point);
364 
365  // call location specific place start function
366  payload_place_start(stopping_point);
367 
368 }
369 
370 // start_command - this function will be called when the ap_mission lib wishes to start a new command
372 {
373  // To-Do: logging when new commands start/end
374  if (copter.should_log(MASK_LOG_CMD)) {
375  copter.DataFlash.Log_Write_Mission_Cmd(copter.mission, cmd);
376  }
377 
378  switch(cmd.id) {
379 
383  case MAV_CMD_NAV_TAKEOFF: // 22
384  do_takeoff(cmd);
385  break;
386 
387  case MAV_CMD_NAV_WAYPOINT: // 16 Navigate to Waypoint
388  do_nav_wp(cmd);
389  break;
390 
391  case MAV_CMD_NAV_LAND: // 21 LAND to Waypoint
392  do_land(cmd);
393  break;
394 
395  case MAV_CMD_NAV_PAYLOAD_PLACE: // 94 place at Waypoint
396  do_payload_place(cmd);
397  break;
398 
399  case MAV_CMD_NAV_LOITER_UNLIM: // 17 Loiter indefinitely
400  do_loiter_unlimited(cmd);
401  break;
402 
403  case MAV_CMD_NAV_LOITER_TURNS: //18 Loiter N Times
404  do_circle(cmd);
405  break;
406 
407  case MAV_CMD_NAV_LOITER_TIME: // 19
408  do_loiter_time(cmd);
409  break;
410 
411  case MAV_CMD_NAV_RETURN_TO_LAUNCH: //20
412  do_RTL();
413  break;
414 
415  case MAV_CMD_NAV_SPLINE_WAYPOINT: // 82 Navigate to Waypoint using spline
416  do_spline_wp(cmd);
417  break;
418 
419 #if NAV_GUIDED == ENABLED
420  case MAV_CMD_NAV_GUIDED_ENABLE: // 92 accept navigation commands from external nav computer
422  break;
423 #endif
424 
425  case MAV_CMD_NAV_DELAY: // 94 Delay the next navigation command
426  do_nav_delay(cmd);
427  break;
428 
429  //
430  // conditional commands
431  //
432  case MAV_CMD_CONDITION_DELAY: // 112
433  do_wait_delay(cmd);
434  break;
435 
436  case MAV_CMD_CONDITION_DISTANCE: // 114
437  do_within_distance(cmd);
438  break;
439 
440  case MAV_CMD_CONDITION_YAW: // 115
441  do_yaw(cmd);
442  break;
443 
447  case MAV_CMD_DO_CHANGE_SPEED: // 178
448  do_change_speed(cmd);
449  break;
450 
451  case MAV_CMD_DO_SET_HOME: // 179
452  do_set_home(cmd);
453  break;
454 
455  case MAV_CMD_DO_SET_SERVO:
456  copter.ServoRelayEvents.do_set_servo(cmd.content.servo.channel, cmd.content.servo.pwm);
457  break;
458 
459  case MAV_CMD_DO_SET_RELAY:
460  copter.ServoRelayEvents.do_set_relay(cmd.content.relay.num, cmd.content.relay.state);
461  break;
462 
463  case MAV_CMD_DO_REPEAT_SERVO:
464  copter.ServoRelayEvents.do_repeat_servo(cmd.content.repeat_servo.channel, cmd.content.repeat_servo.pwm,
466  break;
467 
468  case MAV_CMD_DO_REPEAT_RELAY:
469  copter.ServoRelayEvents.do_repeat_relay(cmd.content.repeat_relay.num, cmd.content.repeat_relay.repeat_count,
470  cmd.content.repeat_relay.cycle_time * 1000.0f);
471  break;
472 
473  case MAV_CMD_DO_SET_ROI: // 201
474  // point the copter and camera at a region of interest (ROI)
475  do_roi(cmd);
476  break;
477 
478  case MAV_CMD_DO_MOUNT_CONTROL: // 205
479  // point the camera to a specified angle
480  do_mount_control(cmd);
481  break;
482 
483  case MAV_CMD_DO_FENCE_ENABLE:
484 #if AC_FENCE == ENABLED
485  if (cmd.p1 == 0) { //disable
486  copter.fence.enable(false);
487  gcs().send_text(MAV_SEVERITY_INFO, "Fence Disabled");
488  } else { //enable fence
489  copter.fence.enable(true);
490  gcs().send_text(MAV_SEVERITY_INFO, "Fence Enabled");
491  }
492 #endif //AC_FENCE == ENABLED
493  break;
494 
495 #if CAMERA == ENABLED
496  case MAV_CMD_DO_CONTROL_VIDEO: // Control on-board camera capturing. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty|
497  break;
498 
499  case MAV_CMD_DO_DIGICAM_CONFIGURE: // Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)|
501  break;
502 
503  case MAV_CMD_DO_DIGICAM_CONTROL: // Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty|
504  do_digicam_control(cmd);
505  break;
506 
507  case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
508  copter.camera.set_trigger_distance(cmd.content.cam_trigg_dist.meters);
509  break;
510 #endif
511 
512 #if PARACHUTE == ENABLED
513  case MAV_CMD_DO_PARACHUTE: // Mission command to configure or release parachute
514  do_parachute(cmd);
515  break;
516 #endif
517 
518 #if GRIPPER_ENABLED == ENABLED
519  case MAV_CMD_DO_GRIPPER: // Mission command to control gripper
520  do_gripper(cmd);
521  break;
522 #endif
523 
524 #if NAV_GUIDED == ENABLED
525  case MAV_CMD_DO_GUIDED_LIMITS: // 220 accept guided mode limits
526  do_guided_limits(cmd);
527  break;
528 #endif
529 
530 #if WINCH_ENABLED == ENABLED
531  case MAV_CMD_DO_WINCH: // Mission command to control winch
532  do_winch(cmd);
533  break;
534 #endif
535 
536  default:
537  // do nothing with unrecognized MAVLink messages
538  break;
539  }
540 
541  // always return success
542  return true;
543 }
544 
545 // verify_command_callback - callback function called from ap-mission at 10hz or higher when a command is being run
546 // we double check that the flight mode is AUTO to avoid the possibility of ap-mission triggering actions while we're not in AUTO mode
548 {
549  if (copter.flightmode == &copter.mode_auto) {
550  bool cmd_complete = verify_command(cmd);
551 
552  // send message to GCS
553  if (cmd_complete) {
555  }
556 
557  return cmd_complete;
558  }
559  return false;
560 }
561 
562 // exit_mission - function that is called once the mission completes
564 {
565  // play a tone
567  // if we are not on the ground switch to loiter or land
568  if(!ap.land_complete) {
569  // try to enter loiter but if that fails land
570  if(!loiter_start()) {
572  }
573  }else{
574  // if we've landed it's safe to disarm
575  copter.init_disarm_motors();
576  }
577 }
578 
579 // do_guided - start guided mode
581 {
582  // only process guided waypoint if we are in guided mode
583  if (copter.control_mode != GUIDED && !(copter.control_mode == AUTO && mode() == Auto_NavGuided)) {
584  return false;
585  }
586 
587  // switch to handle different commands
588  switch (cmd.id) {
589 
590  case MAV_CMD_NAV_WAYPOINT:
591  {
592  // set wp_nav's destination
593  Location_Class dest(cmd.content.location);
594  return copter.mode_guided.set_destination(dest);
595  }
596 
597  case MAV_CMD_CONDITION_YAW:
598  do_yaw(cmd);
599  return true;
600 
601  default:
602  // reject unrecognised command
603  return false;
604  }
605 
606  return true;
607 }
608 
610 {
612 }
613 
615 {
617 }
618 
620 {
621  switch (_mode) {
622  case Auto_NavGuided:
623  return copter.mode_guided.get_wp(destination);
624  case Auto_WP:
625  return wp_nav->get_wp_destination(destination);
626  default:
627  return false;
628  }
629 }
630 
631 // update mission
633 {
634  copter.mission.update();
635 }
636 
637 /*******************************************************************************
638 Verify command Handlers
639 
640 Each type of mission element has a "verify" operation. The verify
641 operation returns true when the mission element has completed and we
642 should move onto the next mission element.
643 Return true if we do not recognize the command so that we move on to the next command
644 *******************************************************************************/
645 
647 {
648  switch(cmd.id) {
649  //
650  // navigation commands
651  //
652  case MAV_CMD_NAV_TAKEOFF:
653  return verify_takeoff();
654 
655  case MAV_CMD_NAV_WAYPOINT:
656  return verify_nav_wp(cmd);
657 
658  case MAV_CMD_NAV_LAND:
659  return verify_land();
660 
661  case MAV_CMD_NAV_PAYLOAD_PLACE:
662  return verify_payload_place();
663 
664  case MAV_CMD_NAV_LOITER_UNLIM:
665  return verify_loiter_unlimited();
666 
667  case MAV_CMD_NAV_LOITER_TURNS:
668  return verify_circle(cmd);
669 
670  case MAV_CMD_NAV_LOITER_TIME:
671  return verify_loiter_time();
672 
673  case MAV_CMD_NAV_RETURN_TO_LAUNCH:
674  return verify_RTL();
675 
676  case MAV_CMD_NAV_SPLINE_WAYPOINT:
677  return verify_spline_wp(cmd);
678 
679 #if NAV_GUIDED == ENABLED
680  case MAV_CMD_NAV_GUIDED_ENABLE:
681  return verify_nav_guided_enable(cmd);
682 #endif
683 
684  case MAV_CMD_NAV_DELAY:
685  return verify_nav_delay(cmd);
686 
690  case MAV_CMD_CONDITION_DELAY:
691  return verify_wait_delay();
692 
693  case MAV_CMD_CONDITION_DISTANCE:
694  return verify_within_distance();
695 
696  case MAV_CMD_CONDITION_YAW:
697  return verify_yaw();
698 
699  // do commands (always return true)
700  case MAV_CMD_DO_CHANGE_SPEED:
701  case MAV_CMD_DO_SET_HOME:
702  case MAV_CMD_DO_SET_SERVO:
703  case MAV_CMD_DO_SET_RELAY:
704  case MAV_CMD_DO_REPEAT_SERVO:
705  case MAV_CMD_DO_REPEAT_RELAY:
706  case MAV_CMD_DO_SET_ROI:
707  case MAV_CMD_DO_MOUNT_CONTROL:
708  case MAV_CMD_DO_CONTROL_VIDEO:
709  case MAV_CMD_DO_DIGICAM_CONFIGURE:
710  case MAV_CMD_DO_DIGICAM_CONTROL:
711  case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
712  case MAV_CMD_DO_PARACHUTE: // assume parachute was released successfully
713  case MAV_CMD_DO_GRIPPER:
714  case MAV_CMD_DO_GUIDED_LIMITS:
715  case MAV_CMD_DO_FENCE_ENABLE:
716  case MAV_CMD_DO_WINCH:
717  return true;
718 
719  default:
720  // error message
721  gcs().send_text(MAV_SEVERITY_WARNING,"Skipping invalid cmd #%i",cmd.id);
722  // return true if we do not recognize the command so that we move on to the next command
723  return true;
724  }
725 }
726 
727 // auto_takeoff_run - takeoff in auto mode
728 // called by auto_run at 100hz or more
730 {
731  // if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
732  if (!motors->armed() || !ap.auto_armed || !motors->get_interlock()) {
733  // initialise wpnav targets
736  // clear i term when we're taking off
738  return;
739  }
740 
741  // process pilot's yaw input
742  float target_yaw_rate = 0;
743  if (!copter.failsafe.radio) {
744  // get pilot's desired yaw rate
746  }
747 
748 #if FRAME_CONFIG == HELI_FRAME
749  // helicopters stay in landed state until rotor speed runup has finished
750  if (motors->rotor_runup_complete()) {
751  set_land_complete(false);
752  } else {
753  // initialise wpnav targets
755  }
756 #else
757  set_land_complete(false);
758 #endif
759 
760  // set motors to full range
761  motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
762 
763  // run waypoint controller
764  copter.failsafe_terrain_set_status(wp_nav->update_wpnav());
765 
766  // call z-axis position controller (wpnav should have already updated it's alt target)
768 
769  // call attitude controller
770  copter.auto_takeoff_attitude_run(target_yaw_rate);
771 }
772 
773 // auto_wp_run - runs the auto waypoint controller
774 // called by auto_run at 100hz or more
776 {
777  // if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
778  if (!motors->armed() || !ap.auto_armed || !motors->get_interlock()) {
779  // To-Do: reset waypoint origin to current location because copter is probably on the ground so we don't want it lurching left or right on take-off
780  // (of course it would be better if people just used take-off)
782  // clear i term when we're taking off
784  return;
785  }
786 
787  // process pilot's yaw input
788  float target_yaw_rate = 0;
789  if (!copter.failsafe.radio) {
790  // get pilot's desired yaw rate
792  if (!is_zero(target_yaw_rate)) {
794  }
795  }
796 
797  // set motors to full range
798  motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
799 
800  // run waypoint controller
801  copter.failsafe_terrain_set_status(wp_nav->update_wpnav());
802 
803  // call z-axis position controller (wpnav should have already updated it's alt target)
805 
806  // call attitude controller
807  if (auto_yaw.mode() == AUTO_YAW_HOLD) {
808  // roll & pitch from waypoint controller, yaw rate from pilot
809  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), target_yaw_rate);
810  } else {
811  // roll, pitch from waypoint controller, yaw heading from auto_heading()
812  attitude_control->input_euler_angle_roll_pitch_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), auto_yaw.yaw(),true);
813  }
814 }
815 
816 // auto_spline_run - runs the auto spline controller
817 // called by auto_run at 100hz or more
819 {
820  // if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
821  if (!motors->armed() || !ap.auto_armed || !motors->get_interlock()) {
822  // To-Do: reset waypoint origin to current location because copter is probably on the ground so we don't want it lurching left or right on take-off
823  // (of course it would be better if people just used take-off)
825  // clear i term when we're taking off
827  return;
828  }
829 
830  // process pilot's yaw input
831  float target_yaw_rate = 0;
832  if (!copter.failsafe.radio) {
833  // get pilot's desired yaw rat
835  if (!is_zero(target_yaw_rate)) {
837  }
838  }
839 
840  // set motors to full range
841  motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
842 
843  // run waypoint controller
845 
846  // call z-axis position controller (wpnav should have already updated it's alt target)
848 
849  // call attitude controller
850  if (auto_yaw.mode() == AUTO_YAW_HOLD) {
851  // roll & pitch from waypoint controller, yaw rate from pilot
852  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), target_yaw_rate);
853  } else {
854  // roll, pitch from waypoint controller, yaw heading from auto_heading()
855  attitude_control->input_euler_angle_roll_pitch_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), auto_yaw.yaw(), true);
856  }
857 }
858 
859 // auto_land_run - lands in auto mode
860 // called by auto_run at 100hz or more
862 {
863  // if not auto armed or landed or motor interlock not enabled set throttle to zero and exit immediately
864  if (!motors->armed() || !ap.auto_armed || ap.land_complete || !motors->get_interlock()) {
866  // set target to current position
868  return;
869  }
870 
871  // set motors to full range
872  motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
873 
876 }
877 
878 // auto_rtl_run - rtl in AUTO flight mode
879 // called by auto_run at 100hz or more
881 {
882  // call regular rtl flight mode run function
883  copter.mode_rtl.run(false);
884 }
885 
886 // auto_circle_run - circle in AUTO flight mode
887 // called by auto_run at 100hz or more
889 {
890  // call circle controller
891  copter.circle_nav->update();
892 
893  // call z-axis position controller
895 
896  // roll & pitch from waypoint controller, yaw rate from pilot
897  attitude_control->input_euler_angle_roll_pitch_yaw(copter.circle_nav->get_roll(), copter.circle_nav->get_pitch(), copter.circle_nav->get_yaw(), true);
898 }
899 
900 #if NAV_GUIDED == ENABLED
901 // auto_nav_guided_run - allows control by external navigation controller
902 // called by auto_run at 100hz or more
904 {
905  // call regular guided flight mode run function
906  copter.mode_guided.run();
907 }
908 #endif // NAV_GUIDED
909 
910 // auto_loiter_run - loiter in AUTO flight mode
911 // called by auto_run at 100hz or more
913 {
914  // if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
915  if (!motors->armed() || !ap.auto_armed || ap.land_complete || !motors->get_interlock()) {
917  return;
918  }
919 
920  // accept pilot input of yaw
921  float target_yaw_rate = 0;
922  if(!copter.failsafe.radio) {
924  }
925 
926  // set motors to full range
927  motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
928 
929  // run waypoint and z-axis position controller
930  copter.failsafe_terrain_set_status(wp_nav->update_wpnav());
931 
933  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), target_yaw_rate);
934 }
935 
936 // auto_payload_place_start - initialises controller to implement placement of a load
938 {
941 
942  // initialise loiter target destination
943  loiter_nav->init_target(destination);
944 
945  // initialise position and desired velocity
946  if (!pos_control->is_active_z()) {
949  }
950 
951  // initialise yaw
953 }
954 
955 // auto_payload_place_run - places an object in auto mode
956 // called by auto_run at 100hz or more
958 {
961  // set target to current position
963  return;
964  }
965 
966  // set motors to full range
967  motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
968 
969  switch (nav_payload_place.state) {
973  return payload_place_run_loiter();
976  return payload_place_run_descend();
983  return payload_place_run_loiter();
984  }
985 }
986 
988 {
989  // muts be armed
990  if (!motors->armed()) {
991  return false;
992  }
993  // muts be auto-armed
994  if (!ap.auto_armed) {
995  return false;
996  }
997  // must not be landed
998  if (ap.land_complete) {
999  return false;
1000  }
1001  // interlock must be enabled (i.e. unsafe)
1002  if (!motors->get_interlock()) {
1003  return false;
1004  }
1005 
1006  return true;
1007 }
1008 
1010 {
1011  // loiter...
1013 
1014  // run loiter controller
1016 
1017  // call attitude controller
1018  const float target_yaw_rate = 0;
1019  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), target_yaw_rate);
1020 
1021  // call position controller
1023 }
1024 
1026 {
1029 }
1030 
1031 // terrain_adjusted_location: returns a Location with lat/lon from cmd
1032 // and altitude from our current altitude adjusted for location
1034 {
1035  // convert to location class
1036  Location_Class target_loc(cmd.content.location);
1037  const Location_Class &current_loc = copter.current_loc;
1038 
1039  // decide if we will use terrain following
1040  int32_t curr_terr_alt_cm, target_terr_alt_cm;
1041  if (current_loc.get_alt_cm(Location_Class::ALT_FRAME_ABOVE_TERRAIN, curr_terr_alt_cm) &&
1042  target_loc.get_alt_cm(Location_Class::ALT_FRAME_ABOVE_TERRAIN, target_terr_alt_cm)) {
1043  curr_terr_alt_cm = MAX(curr_terr_alt_cm,200);
1044  // if using terrain, set target altitude to current altitude above terrain
1045  target_loc.set_alt_cm(curr_terr_alt_cm, Location_Class::ALT_FRAME_ABOVE_TERRAIN);
1046  } else {
1047  // set target altitude to current altitude above home
1048  target_loc.set_alt_cm(current_loc.alt, Location_Class::ALT_FRAME_ABOVE_HOME);
1049  }
1050  return target_loc;
1051 }
1052 
1053 /********************************************************************************/
1054 // Nav (Must) commands
1055 /********************************************************************************/
1056 
1057 // do_takeoff - initiate takeoff navigation command
1059 {
1060  // Set wp navigation target to safe altitude above current position
1062 }
1063 
1064 // do_nav_wp - initiate move to next waypoint
1066 {
1067  Location_Class target_loc(cmd.content.location);
1068  const Location_Class &current_loc = copter.current_loc;
1069 
1070  // use current lat, lon if zero
1071  if (target_loc.lat == 0 && target_loc.lng == 0) {
1072  target_loc.lat = current_loc.lat;
1073  target_loc.lng = current_loc.lng;
1074  }
1075  // use current altitude if not provided
1076  if (target_loc.alt == 0) {
1077  // set to current altitude but in command's alt frame
1078  int32_t curr_alt;
1079  if (current_loc.get_alt_cm(target_loc.get_alt_frame(),curr_alt)) {
1080  target_loc.set_alt_cm(curr_alt, target_loc.get_alt_frame());
1081  } else {
1082  // default to current altitude as alt-above-home
1083  target_loc.set_alt_cm(current_loc.alt, current_loc.get_alt_frame());
1084  }
1085  }
1086 
1087  // this will be used to remember the time in millis after we reach or pass the WP.
1088  loiter_time = 0;
1089  // this is the delay, stored in seconds
1090  loiter_time_max = cmd.p1;
1091 
1092  // Set wp navigation target
1093  wp_start(target_loc);
1094 
1095  // if no delay as well as not final waypoint set the waypoint as "fast"
1096  AP_Mission::Mission_Command temp_cmd;
1097  if (loiter_time_max == 0 && copter.mission.get_next_nav_cmd(cmd.index+1, temp_cmd)) {
1098  copter.wp_nav->set_fast_waypoint(true);
1099  }
1100 }
1101 
1102 // do_land - initiate landing procedure
1104 {
1105  // To-Do: check if we have already landed
1106 
1107  // if location provided we fly to that location at current altitude
1108  if (cmd.content.location.lat != 0 || cmd.content.location.lng != 0) {
1109  // set state to fly to location
1111 
1112  Location_Class target_loc = terrain_adjusted_location(cmd);
1113 
1114  wp_start(target_loc);
1115  }else{
1116  // set landing state
1118 
1119  // initialise landing controller
1120  land_start();
1121  }
1122 }
1123 
1124 // do_loiter_unlimited - start loitering with no end conditions
1125 // note: caller should set yaw_mode
1127 {
1128  // convert back to location
1129  Location_Class target_loc(cmd.content.location);
1130  const Location_Class &current_loc = copter.current_loc;
1131 
1132  // use current location if not provided
1133  if (target_loc.lat == 0 && target_loc.lng == 0) {
1134  // To-Do: make this simpler
1135  Vector3f temp_pos;
1136  copter.wp_nav->get_wp_stopping_point_xy(temp_pos);
1137  Location_Class temp_loc(temp_pos);
1138  target_loc.lat = temp_loc.lat;
1139  target_loc.lng = temp_loc.lng;
1140  }
1141 
1142  // use current altitude if not provided
1143  // To-Do: use z-axis stopping point instead of current alt
1144  if (target_loc.alt == 0) {
1145  // set to current altitude but in command's alt frame
1146  int32_t curr_alt;
1147  if (current_loc.get_alt_cm(target_loc.get_alt_frame(),curr_alt)) {
1148  target_loc.set_alt_cm(curr_alt, target_loc.get_alt_frame());
1149  } else {
1150  // default to current altitude as alt-above-home
1151  target_loc.set_alt_cm(current_loc.alt, current_loc.get_alt_frame());
1152  }
1153  }
1154 
1155  // start way point navigator and provide it the desired location
1156  wp_start(target_loc);
1157 }
1158 
1159 // do_circle - initiate moving in a circle
1161 {
1162  Location_Class circle_center(cmd.content.location);
1163  const Location_Class &current_loc = copter.current_loc;
1164 
1165  // default lat/lon to current position if not provided
1166  // To-Do: use stopping point or position_controller's target instead of current location to avoid jerk?
1167  if (circle_center.lat == 0 && circle_center.lng == 0) {
1168  circle_center.lat = current_loc.lat;
1169  circle_center.lng = current_loc.lng;
1170  }
1171 
1172  // default target altitude to current altitude if not provided
1173  if (circle_center.alt == 0) {
1174  int32_t curr_alt;
1175  if (current_loc.get_alt_cm(circle_center.get_alt_frame(),curr_alt)) {
1176  // circle altitude uses frame from command
1177  circle_center.set_alt_cm(curr_alt,circle_center.get_alt_frame());
1178  } else {
1179  // default to current altitude above origin
1180  circle_center.set_alt_cm(current_loc.alt, current_loc.get_alt_frame());
1182  }
1183  }
1184 
1185  // calculate radius
1186  uint8_t circle_radius_m = HIGHBYTE(cmd.p1); // circle radius held in high byte of p1
1187 
1188  // move to edge of circle (verify_circle) will ensure we begin circling once we reach the edge
1189  circle_movetoedge_start(circle_center, circle_radius_m);
1190 }
1191 
1192 // do_loiter_time - initiate loitering at a point for a given time period
1193 // note: caller should set yaw_mode
1195 {
1196  // re-use loiter unlimited
1197  do_loiter_unlimited(cmd);
1198 
1199  // setup loiter timer
1200  loiter_time = 0;
1201  loiter_time_max = cmd.p1; // units are (seconds)
1202 }
1203 
1204 // do_spline_wp - initiate move to next waypoint
1206 {
1207  Location_Class target_loc(cmd.content.location);
1208  const Location_Class &current_loc = copter.current_loc;
1209 
1210  // use current lat, lon if zero
1211  if (target_loc.lat == 0 && target_loc.lng == 0) {
1212  target_loc.lat = current_loc.lat;
1213  target_loc.lng = current_loc.lng;
1214  }
1215  // use current altitude if not provided
1216  if (target_loc.alt == 0) {
1217  // set to current altitude but in command's alt frame
1218  int32_t curr_alt;
1219  if (current_loc.get_alt_cm(target_loc.get_alt_frame(),curr_alt)) {
1220  target_loc.set_alt_cm(curr_alt, target_loc.get_alt_frame());
1221  } else {
1222  // default to current altitude as alt-above-home
1223  target_loc.set_alt_cm(current_loc.alt, current_loc.get_alt_frame());
1224  }
1225  }
1226 
1227  // this will be used to remember the time in millis after we reach or pass the WP.
1228  loiter_time = 0;
1229  // this is the delay, stored in seconds
1230  loiter_time_max = cmd.p1;
1231 
1232  // determine segment start and end type
1233  bool stopped_at_start = true;
1235  AP_Mission::Mission_Command temp_cmd;
1236 
1237  // if previous command was a wp_nav command with no delay set stopped_at_start to false
1238  // To-Do: move processing of delay into wp-nav controller to allow it to determine the stopped_at_start value itself?
1239  uint16_t prev_cmd_idx = copter.mission.get_prev_nav_cmd_index();
1240  if (prev_cmd_idx != AP_MISSION_CMD_INDEX_NONE) {
1241  if (copter.mission.read_cmd_from_storage(prev_cmd_idx, temp_cmd)) {
1242  if ((temp_cmd.id == MAV_CMD_NAV_WAYPOINT || temp_cmd.id == MAV_CMD_NAV_SPLINE_WAYPOINT) && temp_cmd.p1 == 0) {
1243  stopped_at_start = false;
1244  }
1245  }
1246  }
1247 
1248  // if there is no delay at the end of this segment get next nav command
1249  Location_Class next_loc;
1250  if (cmd.p1 == 0 && copter.mission.get_next_nav_cmd(cmd.index+1, temp_cmd)) {
1251  next_loc = temp_cmd.content.location;
1252  // default lat, lon to first waypoint's lat, lon
1253  if (next_loc.lat == 0 && next_loc.lng == 0) {
1254  next_loc.lat = target_loc.lat;
1255  next_loc.lng = target_loc.lng;
1256  }
1257  // default alt to first waypoint's alt but in next waypoint's alt frame
1258  if (next_loc.alt == 0) {
1259  int32_t next_alt;
1260  if (target_loc.get_alt_cm(next_loc.get_alt_frame(), next_alt)) {
1261  next_loc.set_alt_cm(next_alt, next_loc.get_alt_frame());
1262  } else {
1263  // default to first waypoints altitude
1264  next_loc.set_alt_cm(target_loc.alt, target_loc.get_alt_frame());
1265  }
1266  }
1267  // if the next nav command is a waypoint set end type to spline or straight
1268  if (temp_cmd.id == MAV_CMD_NAV_WAYPOINT) {
1269  seg_end_type = AC_WPNav::SEGMENT_END_STRAIGHT;
1270  }else if (temp_cmd.id == MAV_CMD_NAV_SPLINE_WAYPOINT) {
1271  seg_end_type = AC_WPNav::SEGMENT_END_SPLINE;
1272  }
1273  }
1274 
1275  // set spline navigation target
1276  spline_start(target_loc, stopped_at_start, seg_end_type, next_loc);
1277 }
1278 
1279 #if NAV_GUIDED == ENABLED
1280 // do_nav_guided_enable - initiate accepting commands from external nav computer
1282 {
1283  if (cmd.p1 > 0) {
1284  // initialise guided limits
1285  copter.mode_guided.limit_init_time_and_pos();
1286 
1287  // set spline navigation target
1288  nav_guided_start();
1289  }
1290 }
1291 
1292 // do_guided_limits - pass guided limits to guided controller
1294 {
1295  copter.mode_guided.limit_set(
1296  cmd.p1 * 1000, // convert seconds to ms
1297  cmd.content.guided_limits.alt_min * 100.0f, // convert meters to cm
1298  cmd.content.guided_limits.alt_max * 100.0f, // convert meters to cm
1299  cmd.content.guided_limits.horiz_max * 100.0f); // convert meters to cm
1300 }
1301 #endif // NAV_GUIDED
1302 
1303 // do_nav_delay - Delay the next navigation command
1305 {
1307 
1308  if (cmd.content.nav_delay.seconds > 0) {
1309  // relative delay
1310  nav_delay_time_max = cmd.content.nav_delay.seconds * 1000; // convert seconds to milliseconds
1311  } else {
1312  // absolute delay to utc time
1314  }
1315  gcs().send_text(MAV_SEVERITY_INFO, "Delaying %u sec",(unsigned int)(nav_delay_time_max/1000));
1316 }
1317 
1318 /********************************************************************************/
1319 // Condition (May) commands
1320 /********************************************************************************/
1321 
1323 {
1324  condition_start = millis();
1325  condition_value = cmd.content.delay.seconds * 1000; // convert seconds to milliseconds
1326 }
1327 
1329 {
1330  condition_value = cmd.content.distance.meters * 100;
1331 }
1332 
1334 {
1336  cmd.content.yaw.angle_deg,
1338  cmd.content.yaw.direction,
1339  cmd.content.yaw.relative_angle > 0);
1340 }
1341 
1342 /********************************************************************************/
1343 // Do (Now) commands
1344 /********************************************************************************/
1345 
1346 
1347 
1349 {
1350  if (cmd.content.speed.target_ms > 0) {
1351  copter.wp_nav->set_speed_xy(cmd.content.speed.target_ms * 100.0f);
1352  }
1353 }
1354 
1356 {
1357  if(cmd.p1 == 1 || (cmd.content.location.lat == 0 && cmd.content.location.lng == 0 && cmd.content.location.alt == 0)) {
1358  copter.set_home_to_current_location(false);
1359  } else {
1360  copter.set_home(cmd.content.location, false);
1361  }
1362 }
1363 
1364 // do_roi - starts actions required by MAV_CMD_DO_SET_ROI
1365 // this involves either moving the camera to point at the ROI (region of interest)
1366 // and possibly rotating the copter to point at the ROI if our mount type does not support a yaw feature
1367 // TO-DO: add support for other features of MAV_CMD_DO_SET_ROI including pointing at a given waypoint
1369 {
1371 }
1372 
1373 // point the camera to a specified angle
1375 {
1376 #if MOUNT == ENABLED
1377  if(!copter.camera_mount.has_pan_control()) {
1379  }
1380  copter.camera_mount.set_angle_targets(cmd.content.mount_control.roll, cmd.content.mount_control.pitch, cmd.content.mount_control.yaw);
1381 #endif
1382 }
1383 
1384 #if CAMERA == ENABLED
1385 
1386 // do_digicam_configure Send Digicam Configure message with the camera library
1388 {
1389  copter.camera.configure(
1397 }
1398 
1399 // do_digicam_control Send Digicam Control message with the camera library
1401 {
1402  copter.camera.control(cmd.content.digicam_control.session,
1408 }
1409 
1410 #endif
1411 
1412 #if PARACHUTE == ENABLED
1413 // do_parachute - configure or release parachute
1415 {
1416  switch (cmd.p1) {
1417  case PARACHUTE_DISABLE:
1418  copter.parachute.enabled(false);
1420  break;
1421  case PARACHUTE_ENABLE:
1422  copter.parachute.enabled(true);
1424  break;
1425  case PARACHUTE_RELEASE:
1426  copter.parachute_release();
1427  break;
1428  default:
1429  // do nothing
1430  break;
1431  }
1432 }
1433 #endif
1434 
1435 #if GRIPPER_ENABLED == ENABLED
1436 // do_gripper - control gripper
1438 {
1439  // Note: we ignore the gripper num parameter because we only support one gripper
1440  switch (cmd.content.gripper.action) {
1441  case GRIPPER_ACTION_RELEASE:
1442  g2.gripper.release();
1444  break;
1445  case GRIPPER_ACTION_GRAB:
1446  g2.gripper.grab();
1448  break;
1449  default:
1450  // do nothing
1451  break;
1452  }
1453 }
1454 #endif
1455 
1456 #if WINCH_ENABLED == ENABLED
1457 // control winch based on mission command
1459 {
1460  // Note: we ignore the gripper num parameter because we only support one gripper
1461  switch (cmd.content.winch.action) {
1462  case WINCH_RELAXED:
1463  g2.winch.relax();
1465  break;
1466  case WINCH_RELATIVE_LENGTH_CONTROL:
1469  break;
1470  case WINCH_RATE_CONTROL:
1473  break;
1474  default:
1475  // do nothing
1476  break;
1477  }
1478 }
1479 #endif
1480 
1481 // do_payload_place - initiate placing procedure
1483 {
1484  // if location provided we fly to that location at current altitude
1485  if (cmd.content.location.lat != 0 || cmd.content.location.lng != 0) {
1486  // set state to fly to location
1488 
1489  Location_Class target_loc = terrain_adjusted_location(cmd);
1490 
1491  wp_start(target_loc);
1492  } else {
1494 
1495  // initialise placing controller
1497  }
1498  nav_payload_place.descend_max = cmd.p1;
1499 }
1500 
1501 // do_RTL - start Return-to-Launch
1503 {
1504  // start rtl in auto flight mode
1505  rtl_start();
1506 }
1507 
1508 /********************************************************************************/
1509 // Verify Nav (Must) commands
1510 /********************************************************************************/
1511 
1512 // verify_takeoff - check if we have completed the takeoff
1514 {
1515  // have we reached our target altitude?
1516  return copter.wp_nav->reached_wp_destination();
1517 }
1518 
1519 // verify_land - returns true if landing has been completed
1521 {
1522  bool retval = false;
1523 
1524  switch (land_state) {
1526  // check if we've reached the location
1527  if (copter.wp_nav->reached_wp_destination()) {
1528  // get destination so we can use it for loiter target
1529  Vector3f dest = copter.wp_nav->get_wp_destination();
1530 
1531  // initialise landing controller
1532  land_start(dest);
1533 
1534  // advance to next state
1536  }
1537  break;
1538 
1540  // rely on THROTTLE_LAND mode to correctly update landing status
1541  retval = ap.land_complete;
1542  break;
1543 
1544  default:
1545  // this should never happen
1546  // TO-DO: log an error
1547  retval = true;
1548  break;
1549  }
1550 
1551  // true is returned if we've successfully landed
1552  return retval;
1553 }
1554 
1555 #define NAV_PAYLOAD_PLACE_DEBUGGING 0
1556 
1557 #if NAV_PAYLOAD_PLACE_DEBUGGING
1558 #include <stdio.h>
1559 #define debug(fmt, args ...) do {::fprintf(stderr,"%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
1560 #else
1561 #define debug(fmt, args ...)
1562 #endif
1563 
1564 // verify_payload_place - returns true if placing has been completed
1566 {
1567  const uint16_t hover_throttle_calibrate_time = 2000; // milliseconds
1568  const uint16_t descend_throttle_calibrate_time = 2000; // milliseconds
1569  const float hover_throttle_placed_fraction = 0.7; // i.e. if throttle is less than 70% of hover we have placed
1570  const float descent_throttle_placed_fraction = 0.9; // i.e. if throttle is less than 90% of descent throttle we have placed
1571  const uint16_t placed_time = 500; // how long we have to be below a throttle threshold before considering placed
1572 
1573  const float current_throttle_level = motors->get_throttle();
1574  const uint32_t now = AP_HAL::millis();
1575 
1576  // if we discover we've landed then immediately release the load:
1577  if (ap.land_complete) {
1578  switch (nav_payload_place.state) {
1584  gcs().send_text(MAV_SEVERITY_INFO, "NAV_PLACE: landed");
1586  break;
1593  break;
1594  }
1595  }
1596 
1597  switch (nav_payload_place.state) {
1599  if (!copter.wp_nav->reached_wp_destination()) {
1600  return false;
1601  }
1602  // we're there; set loiter target
1604  FALLTHROUGH;
1606  // hover for 1 second to get an idea of what our hover
1607  // throttle looks like
1608  debug("Calibrate start");
1609  nav_payload_place.hover_start_timestamp = now;
1611  FALLTHROUGH;
1613  if (now - nav_payload_place.hover_start_timestamp < hover_throttle_calibrate_time) {
1614  // still calibrating...
1615  debug("Calibrate Timer: %d", now - nav_payload_place.hover_start_timestamp);
1616  return false;
1617  }
1618  // we have a valid calibration. Hopefully.
1619  nav_payload_place.hover_throttle_level = current_throttle_level;
1620  const float hover_throttle_delta = fabsf(nav_payload_place.hover_throttle_level - motors->get_throttle_hover());
1621  gcs().send_text(MAV_SEVERITY_INFO, "hover throttle delta: %f", static_cast<double>(hover_throttle_delta));
1623  }
1624  FALLTHROUGH;
1626  nav_payload_place.descend_start_timestamp = now;
1627  nav_payload_place.descend_start_altitude = inertial_nav.get_altitude();
1628  nav_payload_place.descend_throttle_level = 0;
1630  FALLTHROUGH;
1632  // make sure we don't descend too far:
1633  debug("descended: %f cm (%f cm max)", (nav_payload_place.descend_start_altitude - inertial_nav.get_altitude()), nav_payload_place.descend_max);
1634  if (!is_zero(nav_payload_place.descend_max) &&
1635  nav_payload_place.descend_start_altitude - inertial_nav.get_altitude() > nav_payload_place.descend_max) {
1637  gcs().send_text(MAV_SEVERITY_WARNING, "Reached maximum descent");
1638  return false; // we'll do any cleanups required next time through the loop
1639  }
1640  // see if we've been descending long enough to calibrate a descend-throttle-level:
1641  if (is_zero(nav_payload_place.descend_throttle_level) &&
1642  now - nav_payload_place.descend_start_timestamp > descend_throttle_calibrate_time) {
1643  nav_payload_place.descend_throttle_level = current_throttle_level;
1644  }
1645  // watch the throttle to determine whether the load has been placed
1646  // debug("hover ratio: %f descend ratio: %f\n", current_throttle_level/nav_payload_place.hover_throttle_level, ((nav_payload_place.descend_throttle_level == 0) ? -1.0f : current_throttle_level/nav_payload_place.descend_throttle_level));
1647  if (current_throttle_level/nav_payload_place.hover_throttle_level > hover_throttle_placed_fraction &&
1648  (is_zero(nav_payload_place.descend_throttle_level) ||
1649  current_throttle_level/nav_payload_place.descend_throttle_level > descent_throttle_placed_fraction)) {
1650  // throttle is above both threshold ratios (or above hover threshold ration and descent threshold ratio not yet valid)
1651  nav_payload_place.place_start_timestamp = 0;
1652  return false;
1653  }
1654  if (nav_payload_place.place_start_timestamp == 0) {
1655  // we've only just now hit the correct throttle level
1656  nav_payload_place.place_start_timestamp = now;
1657  return false;
1658  } else if (now - nav_payload_place.place_start_timestamp < placed_time) {
1659  // keep going down....
1660  debug("Place Timer: %d", now - nav_payload_place.place_start_timestamp);
1661  return false;
1662  }
1664  FALLTHROUGH;
1666 #if GRIPPER_ENABLED == ENABLED
1667  if (g2.gripper.valid()) {
1668  gcs().send_text(MAV_SEVERITY_INFO, "Releasing the gripper");
1669  g2.gripper.release();
1670  } else {
1671  gcs().send_text(MAV_SEVERITY_INFO, "Gripper not valid");
1673  break;
1674  }
1675 #else
1676  gcs().send_text(MAV_SEVERITY_INFO, "Gripper code disabled");
1677 #endif
1679  FALLTHROUGH;
1681 #if GRIPPER_ENABLED == ENABLED
1682  if (g2.gripper.valid() && !g2.gripper.released()) {
1683  return false;
1684  }
1685 #endif
1687  FALLTHROUGH;
1690  }
1691  FALLTHROUGH;
1693  Location_Class target_loc = inertial_nav.get_position();
1694  target_loc.alt = nav_payload_place.descend_start_altitude;
1695  wp_start(target_loc);
1697  }
1698  FALLTHROUGH;
1700  if (!copter.wp_nav->reached_wp_destination()) {
1701  return false;
1702  }
1704  FALLTHROUGH;
1706  return true;
1707  default:
1708  // this should never happen
1709  // TO-DO: log an error
1710  return true;
1711  }
1712  // should never get here
1713  return true;
1714 }
1715 #undef debug
1716 
1718 {
1719  return false;
1720 }
1721 
1722 // verify_loiter_time - check if we have loitered long enough
1724 {
1725  // return immediately if we haven't reached our destination
1726  if (!copter.wp_nav->reached_wp_destination()) {
1727  return false;
1728  }
1729 
1730  // start our loiter timer
1731  if( loiter_time == 0 ) {
1732  loiter_time = millis();
1733  }
1734 
1735  // check if loiter timer has run out
1736  return (((millis() - loiter_time) / 1000) >= loiter_time_max);
1737 }
1738 
1739 // verify_RTL - handles any state changes required to implement RTL
1740 // do_RTL should have been called once first to initialise all variables
1741 // returns true with RTL has completed successfully
1743 {
1744  return (copter.mode_rtl.state_complete() && (copter.mode_rtl.state() == RTL_FinalDescent || copter.mode_rtl.state() == RTL_Land));
1745 }
1746 
1747 /********************************************************************************/
1748 // Verify Condition (May) commands
1749 /********************************************************************************/
1750 
1752 {
1753  if (millis() - condition_start > (uint32_t)MAX(condition_value,0)) {
1754  condition_value = 0;
1755  return true;
1756  }
1757  return false;
1758 }
1759 
1761 {
1762  if (wp_distance() < (uint32_t)MAX(condition_value,0)) {
1763  condition_value = 0;
1764  return true;
1765  }
1766  return false;
1767 }
1768 
1769 // verify_yaw - return true if we have reached the desired heading
1771 {
1772  // set yaw mode if it has been changed (the waypoint controller often retakes control of yaw as it executes a new waypoint command)
1773  if (auto_yaw.mode() != AUTO_YAW_FIXED) {
1775  }
1776 
1777  // check if we are within 2 degrees of the target heading
1778  return (labs(wrap_180_cd(ahrs.yaw_sensor-auto_yaw.yaw())) <= 200);
1779 }
1780 
1781 // verify_nav_wp - check if we have reached the next way point
1783 {
1784  // check if we have reached the waypoint
1785  if( !copter.wp_nav->reached_wp_destination() ) {
1786  return false;
1787  }
1788 
1789  // start timer if necessary
1790  if(loiter_time == 0) {
1791  loiter_time = millis();
1792  }
1793 
1794  // check if timer has run out
1795  if (((millis() - loiter_time) / 1000) >= loiter_time_max) {
1796  // play a tone
1798  gcs().send_text(MAV_SEVERITY_INFO, "Reached command #%i",cmd.index);
1799  return true;
1800  }else{
1801  return false;
1802  }
1803 }
1804 
1805 
1806 
1807 // verify_circle - check if we have circled the point enough
1809 {
1810  // check if we've reached the edge
1811  if (mode() == Auto_CircleMoveToEdge) {
1812  if (copter.wp_nav->reached_wp_destination()) {
1813  const Vector3f curr_pos = copter.inertial_nav.get_position();
1814  Vector3f circle_center = copter.pv_location_to_vector(cmd.content.location);
1815 
1816  // set target altitude if not provided
1817  if (is_zero(circle_center.z)) {
1818  circle_center.z = curr_pos.z;
1819  }
1820 
1821  // set lat/lon position if not provided
1822  if (cmd.content.location.lat == 0 && cmd.content.location.lng == 0) {
1823  circle_center.x = curr_pos.x;
1824  circle_center.y = curr_pos.y;
1825  }
1826 
1827  // start circling
1828  circle_start();
1829  }
1830  return false;
1831  }
1832 
1833  // check if we have completed circling
1834  return fabsf(copter.circle_nav->get_angle_total()/M_2PI) >= LOWBYTE(cmd.p1);
1835 }
1836 
1837 
1838 
1839 // verify_spline_wp - check if we have reached the next way point using spline
1841 {
1842  // check if we have reached the waypoint
1843  if( !copter.wp_nav->reached_wp_destination() ) {
1844  return false;
1845  }
1846 
1847  // start timer if necessary
1848  if(loiter_time == 0) {
1849  loiter_time = millis();
1850  }
1851 
1852  // check if timer has run out
1853  if (((millis() - loiter_time) / 1000) >= loiter_time_max) {
1854  gcs().send_text(MAV_SEVERITY_INFO, "Reached command #%i",cmd.index);
1855  return true;
1856  }else{
1857  return false;
1858  }
1859 }
1860 
1861 #if NAV_GUIDED == ENABLED
1862 // verify_nav_guided - check if we have breached any limits
1864 {
1865  // if disabling guided mode then immediately return true so we move to next command
1866  if (cmd.p1 == 0) {
1867  return true;
1868  }
1869 
1870  // check time and position limits
1871  return copter.mode_guided.limit_check();
1872 }
1873 #endif // NAV_GUIDED
1874 
1875 // verify_nav_delay - check if we have waited long enough
1877 {
1878  if (millis() - nav_delay_time_start > (uint32_t)MAX(nav_delay_time_max,0)) {
1879  nav_delay_time_max = 0;
1880  return true;
1881  }
1882  return false;
1883 }
1884 
1885 #endif
float norm(const T first, const U second, const Params... parameters)
uint32_t condition_start
Definition: Copter.h:375
bool get_vector_from_origin_NEU(Vector3f &vec_neu) const
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
void spline_start(const Vector3f &destination, bool stopped_at_start, AC_WPNav::spline_segment_end_type seg_end_type, const Vector3f &next_spline_destination)
void wp_start(const Vector3f &destination)
Definition: mode_auto.cpp:183
void payload_place_start()
Definition: mode_auto.cpp:359
void set_mode_to_default(bool rtl)
Definition: autoyaw.cpp:28
void send_mission_item_reached_message(uint16_t mission_index)
virtual const Vector3f & get_position() const=0
Mount_Control mount_control
void relax()
bool verify_nav_delay(const AP_Mission::Mission_Command &cmd)
Definition: mode_auto.cpp:1876
Repeat_Servo_Command repeat_servo
int32_t get_pitch() const
spline_segment_end_type
#define FALLTHROUGH
bool set_spline_destination(const Location_Class &destination, bool stopped_at_start, spline_segment_end_type seg_end_type, Location_Class next_destination)
void do_mount_control(const AP_Mission::Mission_Command &cmd)
Definition: mode_auto.cpp:1374
bool do_guided(const AP_Mission::Mission_Command &cmd)
Definition: mode_auto.cpp:580
bool start_command(const AP_Mission::Mission_Command &cmd)
Definition: mode_auto.cpp:371
void do_digicam_control(const AP_Mission::Mission_Command &cmd)
Definition: mode_auto.cpp:1400
void takeoff_start(const Location &dest_loc)
Definition: mode_auto.cpp:136
void do_winch(const AP_Mission::Mission_Command &cmd)
Definition: mode_auto.cpp:1458
void update_z_controller()
void get_wp_stopping_point(Vector3f &stopping_point) const
void do_wait_delay(const AP_Mission::Mission_Command &cmd)
Definition: mode_auto.cpp:1322
GCS_Copter & gcs()
Definition: mode.cpp:587
void set_fixed_yaw(float angle_deg, float turn_rate_dps, int8_t direction, bool relative_angle)
Definition: autoyaw.cpp:101
SEGMENT_END_STRAIGHT
bool update_spline()
void Log_Write_Event(uint8_t id)
Definition: mode.cpp:592
bool verify_payload_place()
Definition: mode_auto.cpp:1565
#define DATA_GRIPPER_RELEASE
Definition: defines.h:368
Definition: defines.h:95
bool verify_loiter_unlimited()
Definition: mode_auto.cpp:1717
#define HIGHBYTE(i)
void run() override
Definition: mode_auto.cpp:57
Digicam_Control digicam_control
Location_Class terrain_adjusted_location(const AP_Mission::Mission_Command &cmd) const
Definition: mode_auto.cpp:1033
#define MASK_LOG_CMD
Definition: defines.h:322
AP_HAL::Util * util
void do_loiter_unlimited(const AP_Mission::Mission_Command &cmd)
Definition: mode_auto.cpp:1126
Definition: defines.h:96
Definition: defines.h:100
uint32_t get_time_utc(int32_t hour, int32_t min, int32_t sec, int32_t ms) const
void do_guided_limits(const AP_Mission::Mission_Command &cmd)
Definition: mode_auto.cpp:1293
int32_t wp_bearing() const override
Definition: mode_auto.cpp:614
Conditional_Delay_Command delay
Repeat_Relay_Command repeat_relay
void do_nav_delay(const AP_Mission::Mission_Command &cmd)
Definition: mode_auto.cpp:1304
AC_AttitudeControl_t *& attitude_control
Definition: Copter.h:123
void init_target(const Vector3f &position)
auto wrap_180_cd(const T angle) -> decltype(wrap_180(angle, 100.f))
bool verify_command(const AP_Mission::Mission_Command &cmd)
Definition: mode_auto.cpp:646
uint32_t wp_distance() const override
Definition: mode_auto.cpp:609
Conditional_Distance_Command distance
void do_digicam_configure(const AP_Mission::Mission_Command &cmd)
Definition: mode_auto.cpp:1387
Navigation_Delay_Command nav_delay
float get_pilot_desired_yaw_rate(int16_t stick_angle)
Definition: mode.cpp:553
int32_t get_roll() const
int32_t nav_delay_time_max
Definition: Copter.h:370
bool verify_loiter_time()
Definition: mode_auto.cpp:1723
void land_run_horizontal_control()
Definition: mode.cpp:449
bool set_wp_destination(const Location_Class &destination)
int32_t lat
Guided_Limits_Command guided_limits
autopilot_yaw_mode mode() const
Definition: Copter.h:26
void land_run_vertical_control(bool pause_descent=false)
Definition: mode.cpp:403
void do_gripper(const AP_Mission::Mission_Command &cmd)
Definition: mode_auto.cpp:1437
bool verify_nav_wp(const AP_Mission::Mission_Command &cmd)
Definition: mode_auto.cpp:1782
int32_t get_wp_bearing_to_destination() const
#define DATA_PARACHUTE_ENABLED
Definition: defines.h:370
void do_nav_guided_enable(const AP_Mission::Mission_Command &cmd)
Definition: mode_auto.cpp:1281
bool verify_circle(const AP_Mission::Mission_Command &cmd)
Definition: mode_auto.cpp:1808
void do_yaw(const AP_Mission::Mission_Command &cmd)
Definition: mode_auto.cpp:1333
AutoMode mode() const
Definition: Copter.h:250
bool update_wpnav()
bool verify_spline_wp(const AP_Mission::Mission_Command &cmd)
Definition: mode_auto.cpp:1840
void payload_place_run_loiter()
Definition: mode_auto.cpp:1009
void set_mode(autopilot_yaw_mode new_mode)
Definition: autoyaw.cpp:59
bool is_active_z() const
AutoMode _mode
Definition: Copter.h:307
Set_Relay_Command relay
void update(float ekfGndSpdLimit, float ekfNavVelGainScaler)
void get_stopping_point_xy(Vector3f &stopping_point) const
int16_t get_control_in() const
#define DATA_WINCH_LENGTH_CONTROL
Definition: defines.h:389
const Vector3f & get_wp_destination() const
int32_t alt
ALT_FRAME get_alt_frame() const
void do_payload_place(const AP_Mission::Mission_Command &cmd)
Definition: mode_auto.cpp:1482
Gripper_Command gripper
#define DATA_PARACHUTE_DISABLED
Definition: defines.h:369
bool verify_nav_guided_enable(const AP_Mission::Mission_Command &cmd)
Definition: mode_auto.cpp:1863
bool is_zero(const T fVal1)
void do_roi(const AP_Mission::Mission_Command &cmd)
Definition: mode_auto.cpp:1368
bool get_alt_cm(ALT_FRAME desired_frame, int32_t &ret_alt_cm) const
#define f(i)
ParametersG2 & g2
Definition: Copter.h:117
bool landing_gear_should_be_deployed() const override
Definition: mode_auto.cpp:345
void set_desired_velocity_z(float vel_z_cms)
void release_length(float length, float rate=0.0f)
const AP_HAL::HAL & hal
Definition: Copter.cpp:21
#define DATA_WINCH_RELAXED
Definition: defines.h:388
void do_circle(const AP_Mission::Mission_Command &cmd)
Definition: mode_auto.cpp:1160
float get_wp_distance_to_destination() const
uint32_t millis()
void do_nav_wp(const AP_Mission::Mission_Command &cmd)
Definition: mode_auto.cpp:1065
AC_WPNav *& wp_nav
Definition: Copter.h:118
void set_throttle_takeoff(void)
Definition: mode.cpp:597
LandStateType land_state
Definition: Copter.h:377
Location_Class current_loc
Definition: Copter.h:475
AP_Winch winch
Definition: Parameters.h:576
#define ERROR_CODE_MISSING_TERRAIN_DATA
Definition: defines.h:436
void shift_wp_origin_to_current_pos()
uint16_t loiter_time_max
Definition: Copter.h:366
void wp_and_spline_init()
Change_Speed_Command speed
#define M_2PI
bool verify_wait_delay()
Definition: mode_auto.cpp:1751
bool verify_within_distance()
Definition: mode_auto.cpp:1760
void do_set_home(const AP_Mission::Mission_Command &cmd)
Definition: mode_auto.cpp:1355
void send_text(MAV_SEVERITY severity, const char *fmt,...)
#define DATA_WINCH_RATE_CONTROL
Definition: defines.h:390
void nav_guided_run()
Definition: mode_auto.cpp:903
DESIRED_THROTTLE_UNLIMITED
void do_change_speed(const AP_Mission::Mission_Command &cmd)
Definition: mode_auto.cpp:1348
AC_PosControl *& pos_control
Definition: Copter.h:120
#define DATA_GRIPPER_GRAB
Definition: defines.h:367
int32_t condition_value
Definition: Copter.h:374
void do_takeoff(const AP_Mission::Mission_Command &cmd)
Definition: mode_auto.cpp:1058
#define LOWBYTE(i)
void do_loiter_time(const AP_Mission::Mission_Command &cmd)
Definition: mode_auto.cpp:1194
void do_parachute(const AP_Mission::Mission_Command &cmd)
Definition: mode_auto.cpp:1414
void run_autopilot() override
Definition: mode_auto.cpp:632
Digicam_Configure digicam_configure
void nav_guided_start()
Definition: mode_auto.cpp:333
bool payload_place_run_should_run()
Definition: mode_auto.cpp:987
void set_alt_cm(int32_t alt_cm, ALT_FRAME frame)
void set_roi(const Location &roi_location)
Definition: autoyaw.cpp:133
int32_t lng
void set_alt_target(float alt_cm)
MOTOR_CLASS *& motors
Definition: Copter.h:124
#define AP_MISSION_CMD_INDEX_NONE
AP_HAL_MAIN_CALLBACKS & copter
Definition: ArduCopter.cpp:581
bool verify_command_callback(const AP_Mission::Mission_Command &cmd)
Definition: mode_auto.cpp:547
#define ERROR_CODE_FAILED_CIRCLE_INIT
Definition: defines.h:440
Set_Servo_Command servo
#define debug(fmt, args ...)
Definition: mode_auto.cpp:1561
Cam_Trigg_Distance cam_trigg_dist
#define ERROR_SUBSYSTEM_TERRAIN
Definition: defines.h:413
uint32_t loiter_time
Definition: Copter.h:367
bool init(bool ignore_checks) override
Definition: mode_auto.cpp:23
void do_spline_wp(const AP_Mission::Mission_Command &cmd)
Definition: mode_auto.cpp:1205
float & ekfNavVelGainScaler
Definition: Copter.h:137
AP_InertialNav & inertial_nav
Definition: Copter.h:121
void do_within_distance(const AP_Mission::Mission_Command &cmd)
Definition: mode_auto.cpp:1328
void payload_place_run_descend()
Definition: mode_auto.cpp:1025
void set_desired_rate(float rate)
void do_RTL(void)
Definition: mode_auto.cpp:1502
AP_AHRS & ahrs
Definition: Copter.h:122
static AutoYaw auto_yaw
Definition: Copter.h:73
RC_Channel *& channel_yaw
Definition: Copter.h:128
static struct notify_events_type events
virtual float get_altitude() const=0
int32_t yaw_sensor
void do_land(const AP_Mission::Mission_Command &cmd)
Definition: mode_auto.cpp:1103
struct Copter::ModeAuto::@7 nav_payload_place
float & ekfGndSpdLimit
Definition: Copter.h:134
void payload_place_run()
Definition: mode_auto.cpp:957
#define ERROR_SUBSYSTEM_NAVIGATION
Definition: defines.h:414
uint32_t nav_delay_time_start
Definition: Copter.h:371
void circle_movetoedge_start(const Location_Class &circle_center, float radius_m)
Definition: mode_auto.cpp:247
void set_land_complete(bool b)
Definition: mode.cpp:582
bool get_wp(Location_Class &loc) override
Definition: mode_auto.cpp:619
Winch_Command winch
AC_Loiter *& loiter_nav
Definition: Copter.h:119