AP_Mount_Alexmos.h 8.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301
  1. /*
  2. Alexmos Serial controlled mount backend class
  3. */
  4. #pragma once
  5. #include "AP_Mount.h"
  6. #include <AP_HAL/AP_HAL.h>
  7. #include <AP_Param/AP_Param.h>
  8. #include <AP_Math/AP_Math.h>
  9. #include <AP_AHRS/AP_AHRS.h>
  10. #include "AP_Mount_Backend.h"
  11. //definition of the commands id for the Alexmos Serial Protocol
  12. #define CMD_READ_PARAMS 'R'
  13. #define CMD_WRITE_PARAMS 'W'
  14. #define CMD_REALTIME_DATA 'D'
  15. #define CMD_BOARD_INFO 'V'
  16. #define CMD_CALIB_ACC 'A'
  17. #define CMD_CALIB_GYRO 'g'
  18. #define CMD_CALIB_EXT_GAIN 'G'
  19. #define CMD_USE_DEFAULTS 'F'
  20. #define CMD_CALIB_POLES 'P'
  21. #define CMD_RESET 'r'
  22. #define CMD_HELPER_DATA 'H'
  23. #define CMD_CALIB_OFFSET 'O'
  24. #define CMD_CALIB_BAT 'B'
  25. #define CMD_MOTORS_ON 'M'
  26. #define CMD_MOTORS_OFF 'm'
  27. #define CMD_CONTROL 'C'
  28. #define CMD_TRIGGER_PIN 'T'
  29. #define CMD_EXECUTE_MENU 'E'
  30. #define CMD_GET_ANGLES 'I'
  31. #define CMD_CONFIRM 'C'
  32. // Board v3.x only
  33. #define CMD_BOARD_INFO_3 20
  34. #define CMD_READ_PARAMS_3 21
  35. #define CMD_WRITE_PARAMS_3 22
  36. #define CMD_REALTIME_DATA_3 23
  37. #define CMD_SELECT_IMU_3 24
  38. #define CMD_READ_PROFILE_NAMES 28
  39. #define CMD_WRITE_PROFILE_NAMES 29
  40. #define CMD_QUEUE_PARAMS_INFO_3 30
  41. #define CMD_SET_PARAMS_3 31
  42. #define CMD_SAVE_PARAMS_3 32
  43. #define CMD_READ_PARAMS_EXT 33
  44. #define CMD_WRITE_PARAMS_EXT 34
  45. #define CMD_AUTO_PID 35
  46. #define CMD_SERVO_OUT 36
  47. #define CMD_ERROR 255
  48. #define AP_MOUNT_ALEXMOS_MODE_NO_CONTROL 0
  49. #define AP_MOUNT_ALEXMOS_MODE_SPEED 1
  50. #define AP_MOUNT_ALEXMOS_MODE_ANGLE 2
  51. #define AP_MOUNT_ALEXMOS_MODE_SPEED_ANGLE 3
  52. #define AP_MOUNT_ALEXMOS_MODE_RC 4
  53. #define AP_MOUNT_ALEXMOS_SPEED 30 // degree/s2
  54. #define VALUE_TO_DEGREE(d) ((float)((d * 720) >> 15))
  55. #define DEGREE_TO_VALUE(d) ((int16_t)((float)(d)*(1.0f/0.02197265625f)))
  56. #define DEGREE_PER_SEC_TO_VALUE(d) ((int16_t)((float)(d)*(1.0f/0.1220740379f)))
  57. class AP_Mount_Alexmos : public AP_Mount_Backend
  58. {
  59. public:
  60. //constructor
  61. AP_Mount_Alexmos(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance):
  62. AP_Mount_Backend(frontend, state, instance)
  63. {}
  64. // init - performs any required initialisation for this instance
  65. void init() override;
  66. // update mount position - should be called periodically
  67. void update() override;
  68. // has_pan_control - returns true if this mount can control it's pan (required for multicopters)
  69. bool has_pan_control() const override;
  70. // set_mode - sets mount's mode
  71. void set_mode(enum MAV_MOUNT_MODE mode) override;
  72. // send_mount_status - called to allow mounts to send their status to GCS via MAVLink
  73. void send_mount_status(mavlink_channel_t chan) override;
  74. private:
  75. // get_angles -
  76. void get_angles();
  77. // set_motor will activate motors if true, and disable them if false
  78. void set_motor(bool on);
  79. // get_boardinfo - get board version and firmware version
  80. void get_boardinfo();
  81. // control_axis - send new angles to the gimbal at a fixed speed of 30 deg/s
  82. void control_axis(const Vector3f& angle , bool targets_in_degrees);
  83. // read_params - read current profile profile_id and global parameters from the gimbal settings
  84. void read_params(uint8_t profile_id);
  85. // write_params - write new parameters to the gimbal settings
  86. void write_params();
  87. bool get_realtimedata( Vector3f& angle);
  88. // Alexmos Serial Protocol reading part implementation
  89. // send_command - send a command to the Alemox Serial API
  90. void send_command(uint8_t cmd, uint8_t* data, uint8_t size);
  91. // Parse the body of the message received from the Alexmos gimbal
  92. void parse_body();
  93. // read_incoming - detect and read the header of the incoming message from the gimbal
  94. void read_incoming();
  95. // structure for the Serial Protocol
  96. // CMD_BOARD_INFO
  97. struct PACKED alexmos_version {
  98. uint8_t _board_version;
  99. uint16_t _firmware_version;
  100. uint8_t debug_mode;
  101. uint16_t _board_features;
  102. };
  103. // CMD_GET_ANGLES
  104. struct PACKED alexmos_angles {
  105. int16_t angle_roll;
  106. int16_t rc_angle_roll;
  107. int16_t rc_speed_roll;
  108. int16_t angle_pitch;
  109. int16_t rc_angle_pitch;
  110. int16_t rc_speed_pitch;
  111. int16_t angle_yaw;
  112. int16_t rc_angle_yaw;
  113. int16_t rc_speed_yaw;
  114. };
  115. // CMD_CONTROL
  116. struct PACKED alexmos_angles_speed {
  117. int8_t mode;
  118. int16_t speed_roll;
  119. int16_t angle_roll;
  120. int16_t speed_pitch;
  121. int16_t angle_pitch;
  122. int16_t speed_yaw;
  123. int16_t angle_yaw;
  124. };
  125. // CMD_READ_PARAMS
  126. struct PACKED alexmos_params {
  127. uint8_t profile_id;
  128. uint8_t roll_P;
  129. uint8_t roll_I;
  130. uint8_t roll_D;
  131. uint8_t roll_power;
  132. uint8_t roll_invert;
  133. uint8_t roll_poles;
  134. uint8_t pitch_P;
  135. uint8_t pitch_I;
  136. uint8_t pitch_D;
  137. uint8_t pitch_power;
  138. uint8_t pitch_invert;
  139. uint8_t pitch_poles;
  140. uint8_t yaw_P;
  141. uint8_t yaw_I;
  142. uint8_t yaw_D;
  143. uint8_t yaw_power;
  144. uint8_t yaw_invert;
  145. uint8_t yaw_poles;
  146. uint8_t acc_limiter;
  147. int8_t ext_fc_gain_roll;
  148. int8_t ext_fc_gain_pitch;
  149. int16_t roll_rc_min_angle;
  150. int16_t roll_rc_max_angle;
  151. uint8_t roll_rc_mode;
  152. uint8_t roll_rc_lpf;
  153. uint8_t roll_rc_speed;
  154. uint8_t roll_rc_follow;
  155. int16_t pitch_rc_min_angle;
  156. int16_t pitch_rc_max_angle;
  157. uint8_t pitch_rc_mode;
  158. uint8_t pitch_rc_lpf;
  159. uint8_t pitch_rc_speed;
  160. uint8_t pitch_rc_follow;
  161. int16_t yaw_rc_min_angle;
  162. int16_t yaw_rc_max_angle;
  163. uint8_t yaw_rc_mode;
  164. uint8_t yaw_rc_lpf;
  165. uint8_t yaw_rc_speed;
  166. uint8_t yaw_rc_follow;
  167. uint8_t gyro_trust;
  168. uint8_t use_model;
  169. uint8_t pwm_freq;
  170. uint8_t serial_speed;
  171. int8_t rc_trim_roll;
  172. int8_t rc_trim_pitch;
  173. int8_t rc_trim_yaw;
  174. uint8_t rc_deadband;
  175. uint8_t rc_expo_rate;
  176. uint8_t rc_virt_mode;
  177. uint8_t rc_map_roll;
  178. uint8_t rc_map_pitch;
  179. uint8_t rc_map_yaw;
  180. uint8_t rc_map_cmd;
  181. uint8_t rc_map_fc_roll;
  182. uint8_t rc_map_fc_pitch;
  183. uint8_t rc_mix_fc_roll;
  184. uint8_t rc_mix_fc_pitch;
  185. uint8_t follow_mode;
  186. uint8_t follow_deadband;
  187. uint8_t follow_expo_rate;
  188. int8_t follow_offset_roll;
  189. int8_t follow_offset_pitch;
  190. int8_t follow_offset_yaw;
  191. int8_t axis_top;
  192. int8_t axis_right;
  193. uint8_t gyro_lpf;
  194. uint8_t gyro_sens;
  195. uint8_t i2c_internal_pullups;
  196. uint8_t sky_gyro_calib;
  197. uint8_t rc_cmd_low;
  198. uint8_t rc_cmd_mid;
  199. uint8_t rc_cmd_high;
  200. uint8_t menu_cmd_1;
  201. uint8_t menu_cmd_2;
  202. uint8_t menu_cmd_3;
  203. uint8_t menu_cmd_4;
  204. uint8_t menu_cmd_5;
  205. uint8_t menu_cmd_long;
  206. uint8_t output_roll;
  207. uint8_t output_pitch;
  208. uint8_t output_yaw;
  209. int16_t bat_threshold_alarm;
  210. int16_t bat_threshold_motors;
  211. int16_t bat_comp_ref;
  212. uint8_t beeper_modes;
  213. uint8_t follow_roll_mix_start;
  214. uint8_t follow_roll_mix_range;
  215. uint8_t booster_power_roll;
  216. uint8_t booster_power_pitch;
  217. uint8_t booster_power_yaw;
  218. uint8_t follow_speed_roll;
  219. uint8_t follow_speed_pitch;
  220. uint8_t follow_speed_yaw;
  221. uint8_t frame_angle_from_motors;
  222. uint8_t cur_profile_id;
  223. };
  224. union PACKED alexmos_parameters {
  225. DEFINE_BYTE_ARRAY_METHODS
  226. alexmos_version version;
  227. alexmos_angles angles;
  228. alexmos_params params;
  229. alexmos_angles_speed angle_speed;
  230. } _buffer,_current_parameters;
  231. AP_HAL::UARTDriver *_port;
  232. bool _initialised : 1;
  233. // result of the get_boardinfo
  234. uint8_t _board_version;
  235. float _current_firmware_version;
  236. uint8_t _firmware_beta_version;
  237. bool _gimbal_3axis : 1;
  238. bool _gimbal_bat_monitoring : 1;
  239. // keep the last _current_angle values
  240. Vector3f _current_angle;
  241. // CMD_READ_PARAMS has been called once
  242. bool _param_read_once : 1;
  243. // Serial Protocol Variables
  244. uint8_t _checksum;
  245. uint8_t _step;
  246. uint8_t _command_id;
  247. uint8_t _payload_length;
  248. uint8_t _payload_counter;
  249. // confirmed that last command was ok
  250. bool _last_command_confirmed : 1;
  251. };