AP_Mount_SToRM32_serial.cpp 8.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279
  1. #include "AP_Mount_SToRM32_serial.h"
  2. #include <AP_HAL/AP_HAL.h>
  3. #include <GCS_MAVLink/GCS_MAVLink.h>
  4. #include <GCS_MAVLink/include/mavlink/v2.0/checksum.h>
  5. #include <AP_GPS/AP_GPS.h>
  6. #include <AP_SerialManager/AP_SerialManager.h>
  7. extern const AP_HAL::HAL& hal;
  8. AP_Mount_SToRM32_serial::AP_Mount_SToRM32_serial(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance) :
  9. AP_Mount_Backend(frontend, state, instance),
  10. _reply_type(ReplyType_UNKNOWN)
  11. {}
  12. // init - performs any required initialisation for this instance
  13. void AP_Mount_SToRM32_serial::init()
  14. {
  15. const AP_SerialManager& serial_manager = AP::serialmanager();
  16. _port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_SToRM32, 0);
  17. if (_port) {
  18. _initialised = true;
  19. set_mode((enum MAV_MOUNT_MODE)_state._default_mode.get());
  20. }
  21. }
  22. // update mount position - should be called periodically
  23. void AP_Mount_SToRM32_serial::update()
  24. {
  25. // exit immediately if not initialised
  26. if (!_initialised) {
  27. return;
  28. }
  29. read_incoming(); // read the incoming messages from the gimbal
  30. // flag to trigger sending target angles to gimbal
  31. bool resend_now = false;
  32. // update based on mount mode
  33. switch(get_mode()) {
  34. // move mount to a "retracted" position. To-Do: remove support and replace with a relaxed mode?
  35. case MAV_MOUNT_MODE_RETRACT:
  36. {
  37. const Vector3f &target = _state._retract_angles.get();
  38. _angle_ef_target_rad.x = ToRad(target.x);
  39. _angle_ef_target_rad.y = ToRad(target.y);
  40. _angle_ef_target_rad.z = ToRad(target.z);
  41. }
  42. break;
  43. // move mount to a neutral position, typically pointing forward
  44. case MAV_MOUNT_MODE_NEUTRAL:
  45. {
  46. const Vector3f &target = _state._neutral_angles.get();
  47. _angle_ef_target_rad.x = ToRad(target.x);
  48. _angle_ef_target_rad.y = ToRad(target.y);
  49. _angle_ef_target_rad.z = ToRad(target.z);
  50. }
  51. break;
  52. // point to the angles given by a mavlink message
  53. case MAV_MOUNT_MODE_MAVLINK_TARGETING:
  54. // 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
  55. resend_now = true;
  56. break;
  57. // RC radio manual angle control, but with stabilization from the AHRS
  58. case MAV_MOUNT_MODE_RC_TARGETING:
  59. // update targets using pilot's rc inputs
  60. update_targets_from_rc();
  61. resend_now = true;
  62. break;
  63. // point mount to a GPS point given by the mission planner
  64. case MAV_MOUNT_MODE_GPS_POINT:
  65. if(AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D) {
  66. calc_angle_to_location(_state._roi_target, _angle_ef_target_rad, true, true);
  67. resend_now = true;
  68. }
  69. break;
  70. default:
  71. // we do not know this mode so do nothing
  72. break;
  73. }
  74. // resend target angles at least once per second
  75. resend_now = resend_now || ((AP_HAL::millis() - _last_send) > AP_MOUNT_STORM32_SERIAL_RESEND_MS);
  76. if ((AP_HAL::millis() - _last_send) > AP_MOUNT_STORM32_SERIAL_RESEND_MS*2) {
  77. _reply_type = ReplyType_UNKNOWN;
  78. }
  79. if (can_send(resend_now)) {
  80. if (resend_now) {
  81. send_target_angles(ToDeg(_angle_ef_target_rad.y), ToDeg(_angle_ef_target_rad.x), ToDeg(_angle_ef_target_rad.z));
  82. get_angles();
  83. _reply_type = ReplyType_ACK;
  84. _reply_counter = 0;
  85. _reply_length = get_reply_size(_reply_type);
  86. } else {
  87. get_angles();
  88. _reply_type = ReplyType_DATA;
  89. _reply_counter = 0;
  90. _reply_length = get_reply_size(_reply_type);
  91. }
  92. }
  93. }
  94. // has_pan_control - returns true if this mount can control it's pan (required for multicopters)
  95. bool AP_Mount_SToRM32_serial::has_pan_control() const
  96. {
  97. // we do not have yaw control
  98. return false;
  99. }
  100. // set_mode - sets mount's mode
  101. void AP_Mount_SToRM32_serial::set_mode(enum MAV_MOUNT_MODE mode)
  102. {
  103. // exit immediately if not initialised
  104. if (!_initialised) {
  105. return;
  106. }
  107. // record the mode change
  108. _state._mode = mode;
  109. }
  110. // send_mount_status - called to allow mounts to send their status to GCS using the MOUNT_STATUS message
  111. void AP_Mount_SToRM32_serial::send_mount_status(mavlink_channel_t chan)
  112. {
  113. // return target angles as gimbal's actual attitude.
  114. mavlink_msg_mount_status_send(chan, 0, 0, _current_angle.y, _current_angle.x, _current_angle.z);
  115. }
  116. bool AP_Mount_SToRM32_serial::can_send(bool with_control) {
  117. uint16_t required_tx = 1;
  118. if (with_control) {
  119. required_tx += sizeof(AP_Mount_SToRM32_serial::cmd_set_angles_struct);
  120. }
  121. return (_reply_type == ReplyType_UNKNOWN) && (_port->txspace() >= required_tx);
  122. }
  123. // send_target_angles
  124. void AP_Mount_SToRM32_serial::send_target_angles(float pitch_deg, float roll_deg, float yaw_deg)
  125. {
  126. static cmd_set_angles_struct cmd_set_angles_data = {
  127. 0xFA,
  128. 0x0E,
  129. 0x11,
  130. 0, // pitch
  131. 0, // roll
  132. 0, // yaw
  133. 0, // flags
  134. 0, // type
  135. 0, // crc
  136. };
  137. // exit immediately if not initialised
  138. if (!_initialised) {
  139. return;
  140. }
  141. if ((size_t)_port->txspace() < sizeof(cmd_set_angles_data)) {
  142. return;
  143. }
  144. // reverse pitch and yaw control
  145. pitch_deg = -pitch_deg;
  146. yaw_deg = -yaw_deg;
  147. // send CMD_SETANGLE
  148. cmd_set_angles_data.pitch = pitch_deg;
  149. cmd_set_angles_data.roll = roll_deg;
  150. cmd_set_angles_data.yaw = yaw_deg;
  151. uint8_t* buf = (uint8_t*)&cmd_set_angles_data;
  152. cmd_set_angles_data.crc = crc_calculate(&buf[1], sizeof(cmd_set_angles_data)-3);
  153. for (uint8_t i = 0; i != sizeof(cmd_set_angles_data) ; i++) {
  154. _port->write(buf[i]);
  155. }
  156. // store time of send
  157. _last_send = AP_HAL::millis();
  158. }
  159. void AP_Mount_SToRM32_serial::get_angles() {
  160. // exit immediately if not initialised
  161. if (!_initialised) {
  162. return;
  163. }
  164. if (_port->txspace() < 1) {
  165. return;
  166. }
  167. _port->write('d');
  168. };
  169. uint8_t AP_Mount_SToRM32_serial::get_reply_size(ReplyType reply_type) {
  170. switch (reply_type) {
  171. case ReplyType_DATA:
  172. return sizeof(SToRM32_reply_data_struct);
  173. break;
  174. case ReplyType_ACK:
  175. return sizeof(SToRM32_reply_ack_struct);
  176. break;
  177. default:
  178. return 0;
  179. }
  180. }
  181. void AP_Mount_SToRM32_serial::read_incoming() {
  182. uint8_t data;
  183. int16_t numc;
  184. numc = _port->available();
  185. if (numc < 0 ){
  186. return;
  187. }
  188. for (int16_t i = 0; i < numc; i++) { // Process bytes received
  189. data = _port->read();
  190. if (_reply_type == ReplyType_UNKNOWN) {
  191. continue;
  192. }
  193. _buffer[_reply_counter++] = data;
  194. if (_reply_counter == _reply_length) {
  195. parse_reply();
  196. switch (_reply_type) {
  197. case ReplyType_ACK:
  198. _reply_type = ReplyType_DATA;
  199. _reply_length = get_reply_size(_reply_type);
  200. _reply_counter = 0;
  201. break;
  202. case ReplyType_DATA:
  203. _reply_type = ReplyType_UNKNOWN;
  204. _reply_length = get_reply_size(_reply_type);
  205. _reply_counter = 0;
  206. break;
  207. default:
  208. _reply_length = get_reply_size(_reply_type);
  209. _reply_counter = 0;
  210. break;
  211. }
  212. }
  213. }
  214. }
  215. void AP_Mount_SToRM32_serial::parse_reply() {
  216. uint16_t crc;
  217. bool crc_ok;
  218. switch (_reply_type) {
  219. case ReplyType_DATA:
  220. crc = crc_calculate(&_buffer[0], sizeof(_buffer.data) - 3);
  221. crc_ok = crc == _buffer.data.crc;
  222. if (!crc_ok) {
  223. break;
  224. }
  225. _current_angle.x = _buffer.data.imu1_roll;
  226. _current_angle.y = _buffer.data.imu1_pitch;
  227. _current_angle.z = _buffer.data.imu1_yaw;
  228. break;
  229. default:
  230. break;
  231. }
  232. }