AP_Mission_Commands.cpp 4.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138
  1. #include "AP_Mission.h"
  2. #include <GCS_MAVLink/GCS.h>
  3. #include <AP_Camera/AP_Camera.h>
  4. #include <AP_Gripper/AP_Gripper.h>
  5. #include <AP_Parachute/AP_Parachute.h>
  6. #include <AP_ServoRelayEvents/AP_ServoRelayEvents.h>
  7. bool AP_Mission::start_command_do_gripper(const AP_Mission::Mission_Command& cmd)
  8. {
  9. AP_Gripper *gripper = AP::gripper();
  10. if (gripper == nullptr) {
  11. return false;
  12. }
  13. // Note: we ignore the gripper num parameter because we only
  14. // support one gripper
  15. switch (cmd.content.gripper.action) {
  16. case GRIPPER_ACTION_RELEASE:
  17. gripper->release();
  18. // Log_Write_Event(DATA_GRIPPER_RELEASE);
  19. gcs().send_text(MAV_SEVERITY_INFO, "Gripper Released");
  20. return true;
  21. case GRIPPER_ACTION_GRAB:
  22. gripper->grab();
  23. // Log_Write_Event(DATA_GRIPPER_GRAB);
  24. gcs().send_text(MAV_SEVERITY_INFO, "Gripper Grabbed");
  25. return true;
  26. default:
  27. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  28. AP_HAL::panic("Unhandled gripper case");
  29. #endif
  30. return false;
  31. }
  32. }
  33. bool AP_Mission::start_command_do_servorelayevents(const AP_Mission::Mission_Command& cmd)
  34. {
  35. AP_ServoRelayEvents *sre = AP::servorelayevents();
  36. if (sre == nullptr) {
  37. return false;
  38. }
  39. switch (cmd.id) {
  40. case MAV_CMD_DO_SET_SERVO:
  41. sre->do_set_servo(cmd.content.servo.channel, cmd.content.servo.pwm);
  42. return true;
  43. case MAV_CMD_DO_SET_RELAY:
  44. sre->do_set_relay(cmd.content.relay.num, cmd.content.relay.state);
  45. return true;
  46. case MAV_CMD_DO_REPEAT_SERVO:
  47. sre->do_repeat_servo(cmd.content.repeat_servo.channel,
  48. cmd.content.repeat_servo.pwm,
  49. cmd.content.repeat_servo.repeat_count,
  50. cmd.content.repeat_servo.cycle_time * 1000.0f);
  51. return true;
  52. case MAV_CMD_DO_REPEAT_RELAY:
  53. sre->do_repeat_relay(cmd.content.repeat_relay.num,
  54. cmd.content.repeat_relay.repeat_count,
  55. cmd.content.repeat_relay.cycle_time * 1000.0f);
  56. return true;
  57. default:
  58. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  59. AP_HAL::panic("Unhandled servo/relay case");
  60. #endif
  61. return false;
  62. }
  63. }
  64. bool AP_Mission::start_command_camera(const AP_Mission::Mission_Command& cmd)
  65. {
  66. AP_Camera *camera = AP::camera();
  67. if (camera == nullptr) {
  68. return false;
  69. }
  70. switch (cmd.id) {
  71. 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)|
  72. camera->configure(
  73. cmd.content.digicam_configure.shooting_mode,
  74. cmd.content.digicam_configure.shutter_speed,
  75. cmd.content.digicam_configure.aperture,
  76. cmd.content.digicam_configure.ISO,
  77. cmd.content.digicam_configure.exposure_type,
  78. cmd.content.digicam_configure.cmd_id,
  79. cmd.content.digicam_configure.engine_cutoff_time);
  80. return true;
  81. 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|
  82. camera->control(
  83. cmd.content.digicam_control.session,
  84. cmd.content.digicam_control.zoom_pos,
  85. cmd.content.digicam_control.zoom_step,
  86. cmd.content.digicam_control.focus_lock,
  87. cmd.content.digicam_control.shooting_cmd,
  88. cmd.content.digicam_control.cmd_id);
  89. return true;
  90. case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
  91. camera->set_trigger_distance(cmd.content.cam_trigg_dist.meters);
  92. return true;
  93. default:
  94. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  95. AP_HAL::panic("Unhandled camera case");
  96. #endif
  97. return false;
  98. }
  99. }
  100. bool AP_Mission::start_command_parachute(const AP_Mission::Mission_Command& cmd)
  101. {
  102. AP_Parachute *parachute = AP::parachute();
  103. if (parachute == nullptr) {
  104. return false;
  105. }
  106. switch (cmd.p1) {
  107. case PARACHUTE_DISABLE:
  108. parachute->enabled(false);
  109. break;
  110. case PARACHUTE_ENABLE:
  111. parachute->enabled(true);
  112. break;
  113. case PARACHUTE_RELEASE:
  114. parachute->release();
  115. break;
  116. default:
  117. // do nothing
  118. return false;
  119. }
  120. return true;
  121. }