AP_Mount_SToRM32.cpp 5.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154
  1. #include "AP_Mount_SToRM32.h"
  2. #include <AP_HAL/AP_HAL.h>
  3. #include <GCS_MAVLink/GCS.h>
  4. #include <AP_GPS/AP_GPS.h>
  5. extern const AP_HAL::HAL& hal;
  6. AP_Mount_SToRM32::AP_Mount_SToRM32(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance) :
  7. AP_Mount_Backend(frontend, state, instance),
  8. _chan(MAVLINK_COMM_0)
  9. {}
  10. // update mount position - should be called periodically
  11. void AP_Mount_SToRM32::update()
  12. {
  13. // exit immediately if not initialised
  14. if (!_initialised) {
  15. find_gimbal();
  16. return;
  17. }
  18. // flag to trigger sending target angles to gimbal
  19. bool resend_now = false;
  20. // update based on mount mode
  21. switch(get_mode()) {
  22. // move mount to a "retracted" position. To-Do: remove support and replace with a relaxed mode?
  23. case MAV_MOUNT_MODE_RETRACT:
  24. {
  25. const Vector3f &target = _state._retract_angles.get();
  26. _angle_ef_target_rad.x = ToRad(target.x);
  27. _angle_ef_target_rad.y = ToRad(target.y);
  28. _angle_ef_target_rad.z = ToRad(target.z);
  29. }
  30. break;
  31. // move mount to a neutral position, typically pointing forward
  32. case MAV_MOUNT_MODE_NEUTRAL:
  33. {
  34. const Vector3f &target = _state._neutral_angles.get();
  35. _angle_ef_target_rad.x = ToRad(target.x);
  36. _angle_ef_target_rad.y = ToRad(target.y);
  37. _angle_ef_target_rad.z = ToRad(target.z);
  38. }
  39. break;
  40. // point to the angles given by a mavlink message
  41. case MAV_MOUNT_MODE_MAVLINK_TARGETING:
  42. // do nothing because earth-frame angle targets (i.e. _angle_ef_target_rad) should have already been set by a MOUNT_CONTROL message from GCS
  43. resend_now = true;
  44. break;
  45. // RC radio manual angle control, but with stabilization from the AHRS
  46. case MAV_MOUNT_MODE_RC_TARGETING:
  47. // update targets using pilot's rc inputs
  48. update_targets_from_rc();
  49. resend_now = true;
  50. break;
  51. // point mount to a GPS point given by the mission planner
  52. case MAV_MOUNT_MODE_GPS_POINT:
  53. if(AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D) {
  54. calc_angle_to_location(_state._roi_target, _angle_ef_target_rad, true, true);
  55. resend_now = true;
  56. }
  57. break;
  58. default:
  59. // we do not know this mode so do nothing
  60. break;
  61. }
  62. // resend target angles at least once per second
  63. if (resend_now || ((AP_HAL::millis() - _last_send) > AP_MOUNT_STORM32_RESEND_MS)) {
  64. send_do_mount_control(ToDeg(_angle_ef_target_rad.y), ToDeg(_angle_ef_target_rad.x), ToDeg(_angle_ef_target_rad.z), MAV_MOUNT_MODE_MAVLINK_TARGETING);
  65. }
  66. }
  67. // has_pan_control - returns true if this mount can control it's pan (required for multicopters)
  68. bool AP_Mount_SToRM32::has_pan_control() const
  69. {
  70. // we do not have yaw control
  71. return false;
  72. }
  73. // set_mode - sets mount's mode
  74. void AP_Mount_SToRM32::set_mode(enum MAV_MOUNT_MODE mode)
  75. {
  76. // exit immediately if not initialised
  77. if (!_initialised) {
  78. return;
  79. }
  80. // record the mode change
  81. _state._mode = mode;
  82. }
  83. // send_mount_status - called to allow mounts to send their status to GCS using the MOUNT_STATUS message
  84. void AP_Mount_SToRM32::send_mount_status(mavlink_channel_t chan)
  85. {
  86. // return target angles as gimbal's actual attitude. To-Do: retrieve actual gimbal attitude and send these instead
  87. mavlink_msg_mount_status_send(chan, 0, 0, ToDeg(_angle_ef_target_rad.y)*100, ToDeg(_angle_ef_target_rad.x)*100, ToDeg(_angle_ef_target_rad.z)*100);
  88. }
  89. // search for gimbal in GCS_MAVLink routing table
  90. void AP_Mount_SToRM32::find_gimbal()
  91. {
  92. // return immediately if initialised
  93. if (_initialised) {
  94. return;
  95. }
  96. // return if search time has has passed
  97. if (AP_HAL::millis() > AP_MOUNT_STORM32_SEARCH_MS) {
  98. return;
  99. }
  100. if (GCS_MAVLINK::find_by_mavtype(MAV_TYPE_GIMBAL, _sysid, _compid, _chan)) {
  101. _initialised = true;
  102. }
  103. }
  104. // send_do_mount_control - send a COMMAND_LONG containing a do_mount_control message
  105. void AP_Mount_SToRM32::send_do_mount_control(float pitch_deg, float roll_deg, float yaw_deg, enum MAV_MOUNT_MODE mount_mode)
  106. {
  107. // exit immediately if not initialised
  108. if (!_initialised) {
  109. return;
  110. }
  111. // check we have space for the message
  112. if (!HAVE_PAYLOAD_SPACE(_chan, COMMAND_LONG)) {
  113. return;
  114. }
  115. // reverse pitch and yaw control
  116. pitch_deg = -pitch_deg;
  117. yaw_deg = -yaw_deg;
  118. // send command_long command containing a do_mount_control command
  119. mavlink_msg_command_long_send(_chan,
  120. _sysid,
  121. _compid,
  122. MAV_CMD_DO_MOUNT_CONTROL,
  123. 0, // confirmation of zero means this is the first time this message has been sent
  124. pitch_deg,
  125. roll_deg,
  126. yaw_deg,
  127. 0, 0, 0, // param4 ~ param6 unused
  128. mount_mode);
  129. // store time of send
  130. _last_send = AP_HAL::millis();
  131. }