AP_Mount_Alexmos.cpp 8.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288
  1. #include "AP_Mount_Alexmos.h"
  2. #include <AP_GPS/AP_GPS.h>
  3. #include <AP_SerialManager/AP_SerialManager.h>
  4. extern const AP_HAL::HAL& hal;
  5. void AP_Mount_Alexmos::init()
  6. {
  7. const AP_SerialManager& serial_manager = AP::serialmanager();
  8. // check for alexmos protcol
  9. if ((_port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_AlexMos, 0))) {
  10. _initialised = true;
  11. get_boardinfo();
  12. read_params(0); //we request parameters for profile 0 and therfore get global and profile parameters
  13. }
  14. }
  15. // update mount position - should be called periodically
  16. void AP_Mount_Alexmos::update()
  17. {
  18. if (!_initialised) {
  19. return;
  20. }
  21. read_incoming(); // read the incoming messages from the gimbal
  22. // update based on mount mode
  23. switch(get_mode()) {
  24. // move mount to a "retracted" position. we do not implement a separate servo based retract mechanism
  25. case MAV_MOUNT_MODE_RETRACT:
  26. control_axis(_state._retract_angles.get(), true);
  27. break;
  28. // move mount to a neutral position, typically pointing forward
  29. case MAV_MOUNT_MODE_NEUTRAL:
  30. control_axis(_state._neutral_angles.get(), true);
  31. break;
  32. // point to the angles given by a mavlink message
  33. case MAV_MOUNT_MODE_MAVLINK_TARGETING:
  34. // 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
  35. control_axis(_angle_ef_target_rad, false);
  36. break;
  37. // RC radio manual angle control, but with stabilization from the AHRS
  38. case MAV_MOUNT_MODE_RC_TARGETING:
  39. // update targets using pilot's rc inputs
  40. update_targets_from_rc();
  41. control_axis(_angle_ef_target_rad, false);
  42. break;
  43. // point mount to a GPS point given by the mission planner
  44. case MAV_MOUNT_MODE_GPS_POINT:
  45. if(AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D) {
  46. calc_angle_to_location(_state._roi_target, _angle_ef_target_rad, true, false);
  47. control_axis(_angle_ef_target_rad, false);
  48. }
  49. break;
  50. default:
  51. // we do not know this mode so do nothing
  52. break;
  53. }
  54. }
  55. // has_pan_control - returns true if this mount can control it's pan (required for multicopters)
  56. bool AP_Mount_Alexmos::has_pan_control() const
  57. {
  58. return _gimbal_3axis;
  59. }
  60. // set_mode - sets mount's mode
  61. void AP_Mount_Alexmos::set_mode(enum MAV_MOUNT_MODE mode)
  62. {
  63. // record the mode change and return success
  64. _state._mode = mode;
  65. }
  66. // send_mount_status - called to allow mounts to send their status to GCS using the MOUNT_STATUS message
  67. void AP_Mount_Alexmos::send_mount_status(mavlink_channel_t chan)
  68. {
  69. if (!_initialised) {
  70. return;
  71. }
  72. get_angles();
  73. mavlink_msg_mount_status_send(chan, 0, 0, _current_angle.y*100, _current_angle.x*100, _current_angle.z*100);
  74. }
  75. /*
  76. * get_angles
  77. */
  78. void AP_Mount_Alexmos::get_angles()
  79. {
  80. uint8_t data[1] = {(uint8_t)1};
  81. send_command(CMD_GET_ANGLES, data, 1);
  82. }
  83. /*
  84. * set_motor will activate motors if true, and disable them if false.
  85. */
  86. void AP_Mount_Alexmos::set_motor(bool on)
  87. {
  88. if (on) {
  89. uint8_t data[1] = {(uint8_t)1};
  90. send_command(CMD_MOTORS_ON, data, 1);
  91. } else {
  92. uint8_t data[1] = {(uint8_t)1};
  93. send_command(CMD_MOTORS_OFF, data, 1);
  94. }
  95. }
  96. /*
  97. * get board version and firmware version
  98. */
  99. void AP_Mount_Alexmos::get_boardinfo()
  100. {
  101. if (_board_version != 0) {
  102. return;
  103. }
  104. uint8_t data[1] = {(uint8_t)1};
  105. send_command(CMD_BOARD_INFO, data, 1);
  106. }
  107. /*
  108. control_axis : send new angles to the gimbal at a fixed speed of 30 deg/s2
  109. */
  110. void AP_Mount_Alexmos::control_axis(const Vector3f& angle, bool target_in_degrees)
  111. {
  112. // convert to degrees if necessary
  113. Vector3f target_deg = angle;
  114. if (!target_in_degrees) {
  115. target_deg *= RAD_TO_DEG;
  116. }
  117. alexmos_parameters outgoing_buffer;
  118. outgoing_buffer.angle_speed.mode = AP_MOUNT_ALEXMOS_MODE_ANGLE;
  119. outgoing_buffer.angle_speed.speed_roll = DEGREE_PER_SEC_TO_VALUE(AP_MOUNT_ALEXMOS_SPEED);
  120. outgoing_buffer.angle_speed.angle_roll = DEGREE_TO_VALUE(target_deg.x);
  121. outgoing_buffer.angle_speed.speed_pitch = DEGREE_PER_SEC_TO_VALUE(AP_MOUNT_ALEXMOS_SPEED);
  122. outgoing_buffer.angle_speed.angle_pitch = DEGREE_TO_VALUE(target_deg.y);
  123. outgoing_buffer.angle_speed.speed_yaw = DEGREE_PER_SEC_TO_VALUE(AP_MOUNT_ALEXMOS_SPEED);
  124. outgoing_buffer.angle_speed.angle_yaw = DEGREE_TO_VALUE(target_deg.z);
  125. send_command(CMD_CONTROL, (uint8_t *)&outgoing_buffer.angle_speed, sizeof(alexmos_angles_speed));
  126. }
  127. /*
  128. read current profile profile_id and global parameters from the gimbal settings
  129. */
  130. void AP_Mount_Alexmos::read_params(uint8_t profile_id)
  131. {
  132. uint8_t data[1] = {(uint8_t) profile_id};
  133. send_command(CMD_READ_PARAMS, data, 1);
  134. }
  135. /*
  136. write new parameters to the gimbal settings
  137. */
  138. void AP_Mount_Alexmos::write_params()
  139. {
  140. if (!_param_read_once) {
  141. return;
  142. }
  143. send_command(CMD_WRITE_PARAMS, (uint8_t *)&_current_parameters.params, sizeof(alexmos_params));
  144. }
  145. /*
  146. send a command to the Alemox Serial API
  147. */
  148. void AP_Mount_Alexmos::send_command(uint8_t cmd, uint8_t* data, uint8_t size)
  149. {
  150. if (_port->txspace() < (size + 5U)) {
  151. return;
  152. }
  153. uint8_t checksum = 0;
  154. _port->write( '>' );
  155. _port->write( cmd ); // write command id
  156. _port->write( size ); // write body size
  157. _port->write( cmd+size ); // write header checkum
  158. for (uint8_t i = 0; i != size ; i++) {
  159. checksum += data[i];
  160. _port->write( data[i] );
  161. }
  162. _port->write(checksum);
  163. }
  164. /*
  165. * Parse the body of the message received from the Alexmos gimbal
  166. */
  167. void AP_Mount_Alexmos::parse_body()
  168. {
  169. switch (_command_id ) {
  170. case CMD_BOARD_INFO:
  171. _board_version = _buffer.version._board_version/ 10;
  172. _current_firmware_version = _buffer.version._firmware_version / 1000.0f ;
  173. _firmware_beta_version = _buffer.version._firmware_version % 10 ;
  174. _gimbal_3axis = (_buffer.version._board_features & 0x1);
  175. _gimbal_bat_monitoring = (_buffer.version._board_features & 0x2);
  176. break;
  177. case CMD_GET_ANGLES:
  178. _current_angle.x = VALUE_TO_DEGREE(_buffer.angles.angle_roll);
  179. _current_angle.y = VALUE_TO_DEGREE(_buffer.angles.angle_pitch);
  180. _current_angle.z = VALUE_TO_DEGREE(_buffer.angles.angle_yaw);
  181. break;
  182. case CMD_READ_PARAMS:
  183. _param_read_once = true;
  184. _current_parameters.params = _buffer.params;
  185. break;
  186. case CMD_WRITE_PARAMS:
  187. break;
  188. default :
  189. _last_command_confirmed = true;
  190. break;
  191. }
  192. }
  193. /*
  194. * detect and read the header of the incoming message from the gimbal
  195. */
  196. void AP_Mount_Alexmos::read_incoming()
  197. {
  198. uint8_t data;
  199. int16_t numc;
  200. numc = _port->available();
  201. if (numc < 0 ){
  202. return;
  203. }
  204. for (int16_t i = 0; i < numc; i++) { // Process bytes received
  205. data = _port->read();
  206. switch (_step) {
  207. case 0:
  208. if ( '>' == data) {
  209. _step = 1;
  210. _checksum = 0; //reset checksum accumulator
  211. _last_command_confirmed = false;
  212. }
  213. break;
  214. case 1: // command ID
  215. _checksum = data;
  216. _command_id = data;
  217. _step++;
  218. break;
  219. case 2: // Size of the body of the message
  220. _checksum += data;
  221. _payload_length = data;
  222. _step++;
  223. break;
  224. case 3: // checksum of the header
  225. if (_checksum != data ) {
  226. _step = 0;
  227. _checksum = 0;
  228. // checksum error
  229. break;
  230. }
  231. _step++;
  232. _checksum = 0;
  233. _payload_counter = 0; // prepare to receive payload
  234. break;
  235. case 4: // parsing body
  236. _checksum += data;
  237. if (_payload_counter < sizeof(_buffer)) {
  238. _buffer[_payload_counter] = data;
  239. }
  240. if (++_payload_counter == _payload_length)
  241. _step++;
  242. break;
  243. case 5:// body checksum
  244. _step = 0;
  245. if (_checksum != data) {
  246. break;
  247. }
  248. parse_body();
  249. }
  250. }
  251. }