AP_Mount.cpp 25 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709
  1. #include <AP_Common/AP_Common.h>
  2. #include <AP_Param/AP_Param.h>
  3. #include "AP_Mount.h"
  4. #include "AP_Mount_Backend.h"
  5. #include "AP_Mount_Servo.h"
  6. #include "AP_Mount_SoloGimbal.h"
  7. #include "AP_Mount_Alexmos.h"
  8. #include "AP_Mount_SToRM32.h"
  9. #include "AP_Mount_SToRM32_serial.h"
  10. const AP_Param::GroupInfo AP_Mount::var_info[] = {
  11. // @Param: _DEFLT_MODE
  12. // @DisplayName: Mount default operating mode
  13. // @Description: Mount default operating mode on startup and after control is returned from autopilot
  14. // @Values: 0:Retracted,1:Neutral,2:MavLink Targeting,3:RC Targeting,4:GPS Point
  15. // @User: Standard
  16. AP_GROUPINFO("_DEFLT_MODE", 0, AP_Mount, state[0]._default_mode, MAV_MOUNT_MODE_RC_TARGETING),
  17. // @Param: _RETRACT_X
  18. // @DisplayName: Mount roll angle when in retracted position
  19. // @Description: Mount roll angle when in retracted position
  20. // @Units: deg
  21. // @Range: -180.00 179.99
  22. // @Increment: 1
  23. // @User: Standard
  24. // @Param: _RETRACT_Y
  25. // @DisplayName: Mount tilt/pitch angle when in retracted position
  26. // @Description: Mount tilt/pitch angle when in retracted position
  27. // @Units: deg
  28. // @Range: -180.00 179.99
  29. // @Increment: 1
  30. // @User: Standard
  31. // @Param: _RETRACT_Z
  32. // @DisplayName: Mount yaw/pan angle when in retracted position
  33. // @Description: Mount yaw/pan angle when in retracted position
  34. // @Units: deg
  35. // @Range: -180.00 179.99
  36. // @Increment: 1
  37. // @User: Standard
  38. AP_GROUPINFO("_RETRACT", 1, AP_Mount, state[0]._retract_angles, 0),
  39. // @Param: _NEUTRAL_X
  40. // @DisplayName: Mount roll angle when in neutral position
  41. // @Description: Mount roll angle when in neutral position
  42. // @Units: deg
  43. // @Range: -180.00 179.99
  44. // @Increment: 1
  45. // @User: Standard
  46. // @Param: _NEUTRAL_Y
  47. // @DisplayName: Mount tilt/pitch angle when in neutral position
  48. // @Description: Mount tilt/pitch angle when in neutral position
  49. // @Units: deg
  50. // @Range: -180.00 179.99
  51. // @Increment: 1
  52. // @User: Standard
  53. // @Param: _NEUTRAL_Z
  54. // @DisplayName: Mount pan/yaw angle when in neutral position
  55. // @Description: Mount pan/yaw angle when in neutral position
  56. // @Units: deg
  57. // @Range: -180.00 179.99
  58. // @Increment: 1
  59. // @User: Standard
  60. AP_GROUPINFO("_NEUTRAL", 2, AP_Mount, state[0]._neutral_angles, 0),
  61. // 3 was used for control_angles
  62. // @Param: _STAB_ROLL
  63. // @DisplayName: Stabilize mount's roll angle
  64. // @Description: enable roll stabilisation relative to Earth
  65. // @Values: 0:Disabled,1:Enabled
  66. // @User: Standard
  67. AP_GROUPINFO("_STAB_ROLL", 4, AP_Mount, state[0]._stab_roll, 0),
  68. // @Param: _STAB_TILT
  69. // @DisplayName: Stabilize mount's pitch/tilt angle
  70. // @Description: enable tilt/pitch stabilisation relative to Earth
  71. // @Values: 0:Disabled,1:Enabled
  72. // @User: Standard
  73. AP_GROUPINFO("_STAB_TILT", 5, AP_Mount, state[0]._stab_tilt, 0),
  74. // @Param: _STAB_PAN
  75. // @DisplayName: Stabilize mount pan/yaw angle
  76. // @Description: enable pan/yaw stabilisation relative to Earth
  77. // @Values: 0:Disabled,1:Enabled
  78. // @User: Standard
  79. AP_GROUPINFO("_STAB_PAN", 6, AP_Mount, state[0]._stab_pan, 0),
  80. // @Param: _RC_IN_ROLL
  81. // @DisplayName: roll RC input channel
  82. // @Description: 0 for none, any other for the RC channel to be used to control roll movements
  83. // @Values: 0:Disabled,5:RC5,6:RC6,7:RC7,8:RC8,9:RC9,10:RC10,11:RC11,12:RC12
  84. // @User: Standard
  85. AP_GROUPINFO("_RC_IN_ROLL", 7, AP_Mount, state[0]._roll_rc_in, 0),
  86. // @Param: _ANGMIN_ROL
  87. // @DisplayName: Minimum roll angle
  88. // @Description: Minimum physical roll angular position of mount.
  89. // @Units: cdeg
  90. // @Range: -18000 17999
  91. // @Increment: 1
  92. // @User: Standard
  93. AP_GROUPINFO("_ANGMIN_ROL", 8, AP_Mount, state[0]._roll_angle_min, -4500),
  94. // @Param: _ANGMAX_ROL
  95. // @DisplayName: Maximum roll angle
  96. // @Description: Maximum physical roll angular position of the mount
  97. // @Units: cdeg
  98. // @Range: -18000 17999
  99. // @Increment: 1
  100. // @User: Standard
  101. AP_GROUPINFO("_ANGMAX_ROL", 9, AP_Mount, state[0]._roll_angle_max, 4500),
  102. // @Param: _RC_IN_TILT
  103. // @DisplayName: tilt (pitch) RC input channel
  104. // @Description: 0 for none, any other for the RC channel to be used to control tilt (pitch) movements
  105. // @Values: 0:Disabled,5:RC5,6:RC6,7:RC7,8:RC8,9:RC9,10:RC10,11:RC11,12:RC12
  106. // @User: Standard
  107. AP_GROUPINFO("_RC_IN_TILT", 10, AP_Mount, state[0]._tilt_rc_in, 0),
  108. // @Param: _ANGMIN_TIL
  109. // @DisplayName: Minimum tilt angle
  110. // @Description: Minimum physical tilt (pitch) angular position of mount.
  111. // @Units: cdeg
  112. // @Range: -18000 17999
  113. // @Increment: 1
  114. // @User: Standard
  115. AP_GROUPINFO("_ANGMIN_TIL", 11, AP_Mount, state[0]._tilt_angle_min, -4500),
  116. // @Param: _ANGMAX_TIL
  117. // @DisplayName: Maximum tilt angle
  118. // @Description: Maximum physical tilt (pitch) angular position of the mount
  119. // @Units: cdeg
  120. // @Range: -18000 17999
  121. // @Increment: 1
  122. // @User: Standard
  123. AP_GROUPINFO("_ANGMAX_TIL", 12, AP_Mount, state[0]._tilt_angle_max, 4500),
  124. // @Param: _RC_IN_PAN
  125. // @DisplayName: pan (yaw) RC input channel
  126. // @Description: 0 for none, any other for the RC channel to be used to control pan (yaw) movements
  127. // @Values: 0:Disabled,5:RC5,6:RC6,7:RC7,8:RC8,9:RC9,10:RC10,11:RC11,12:RC12
  128. // @User: Standard
  129. AP_GROUPINFO("_RC_IN_PAN", 13, AP_Mount, state[0]._pan_rc_in, 0),
  130. // @Param: _ANGMIN_PAN
  131. // @DisplayName: Minimum pan angle
  132. // @Description: Minimum physical pan (yaw) angular position of mount.
  133. // @Units: cdeg
  134. // @Range: -18000 17999
  135. // @Increment: 1
  136. // @User: Standard
  137. AP_GROUPINFO("_ANGMIN_PAN", 14, AP_Mount, state[0]._pan_angle_min, -4500),
  138. // @Param: _ANGMAX_PAN
  139. // @DisplayName: Maximum pan angle
  140. // @Description: Maximum physical pan (yaw) angular position of the mount
  141. // @Units: cdeg
  142. // @Range: -18000 17999
  143. // @Increment: 1
  144. // @User: Standard
  145. AP_GROUPINFO("_ANGMAX_PAN", 15, AP_Mount, state[0]._pan_angle_max, 4500),
  146. // @Param: _JSTICK_SPD
  147. // @DisplayName: mount joystick speed
  148. // @Description: 0 for position control, small for low speeds, 100 for max speed. A good general value is 10 which gives a movement speed of 3 degrees per second.
  149. // @Range: 0 100
  150. // @Increment: 1
  151. // @User: Standard
  152. AP_GROUPINFO("_JSTICK_SPD", 16, AP_Mount, _joystick_speed, 0),
  153. // @Param: _LEAD_RLL
  154. // @DisplayName: Roll stabilization lead time
  155. // @Description: Causes the servo angle output to lead the current angle of the vehicle by some amount of time based on current angular rate, compensating for servo delay. Increase until the servo is responsive but doesn't overshoot. Does nothing with pan stabilization enabled.
  156. // @Units: s
  157. // @Range: 0.0 0.2
  158. // @Increment: .005
  159. // @User: Standard
  160. AP_GROUPINFO("_LEAD_RLL", 17, AP_Mount, state[0]._roll_stb_lead, 0.0f),
  161. // @Param: _LEAD_PTCH
  162. // @DisplayName: Pitch stabilization lead time
  163. // @Description: Causes the servo angle output to lead the current angle of the vehicle by some amount of time based on current angular rate. Increase until the servo is responsive but doesn't overshoot. Does nothing with pan stabilization enabled.
  164. // @Units: s
  165. // @Range: 0.0 0.2
  166. // @Increment: .005
  167. // @User: Standard
  168. AP_GROUPINFO("_LEAD_PTCH", 18, AP_Mount, state[0]._pitch_stb_lead, 0.0f),
  169. // @Param: _TYPE
  170. // @DisplayName: Mount Type
  171. // @Description: Mount Type (None, Servo or MAVLink)
  172. // @Values: 0:None, 1:Servo, 2:3DR Solo, 3:Alexmos Serial, 4:SToRM32 MAVLink, 5:SToRM32 Serial
  173. // @RebootRequired: True
  174. // @User: Standard
  175. AP_GROUPINFO("_TYPE", 19, AP_Mount, state[0]._type, 0),
  176. // 20 formerly _OFF_JNT
  177. // 21 formerly _OFF_ACC
  178. // 22 formerly _OFF_GYRO
  179. // 23 formerly _K_RATE
  180. // 24 is AVAILABLE
  181. #if AP_MOUNT_MAX_INSTANCES > 1
  182. // @Param: 2_DEFLT_MODE
  183. // @DisplayName: Mount default operating mode
  184. // @Description: Mount default operating mode on startup and after control is returned from autopilot
  185. // @Values: 0:Retracted,1:Neutral,2:MavLink Targeting,3:RC Targeting,4:GPS Point
  186. // @User: Standard
  187. AP_GROUPINFO("2_DEFLT_MODE", 25, AP_Mount, state[1]._default_mode, MAV_MOUNT_MODE_RC_TARGETING),
  188. // @Param: 2_RETRACT_X
  189. // @DisplayName: Mount2 roll angle when in retracted position
  190. // @Description: Mount2 roll angle when in retracted position
  191. // @Units: deg
  192. // @Range: -180.00 179.99
  193. // @Increment: 1
  194. // @User: Standard
  195. // @Param: 2_RETRACT_Y
  196. // @DisplayName: Mount2 tilt/pitch angle when in retracted position
  197. // @Description: Mount2 tilt/pitch angle when in retracted position
  198. // @Units: deg
  199. // @Range: -180.00 179.99
  200. // @Increment: 1
  201. // @User: Standard
  202. // @Param: 2_RETRACT_Z
  203. // @DisplayName: Mount2 yaw/pan angle when in retracted position
  204. // @Description: Mount2 yaw/pan angle when in retracted position
  205. // @Units: deg
  206. // @Range: -180.00 179.99
  207. // @Increment: 1
  208. // @User: Standard
  209. AP_GROUPINFO("2_RETRACT", 26, AP_Mount, state[1]._retract_angles, 0),
  210. // @Param: 2_NEUTRAL_X
  211. // @DisplayName: Mount2 roll angle when in neutral position
  212. // @Description: Mount2 roll angle when in neutral position
  213. // @Units: deg
  214. // @Range: -180.00 179.99
  215. // @Increment: 1
  216. // @User: Standard
  217. // @Param: 2_NEUTRAL_Y
  218. // @DisplayName: Mount2 tilt/pitch angle when in neutral position
  219. // @Description: Mount2 tilt/pitch angle when in neutral position
  220. // @Units: deg
  221. // @Range: -180.00 179.99
  222. // @Increment: 1
  223. // @User: Standard
  224. // @Param: 2_NEUTRAL_Z
  225. // @DisplayName: Mount2 pan/yaw angle when in neutral position
  226. // @Description: Mount2 pan/yaw angle when in neutral position
  227. // @Units: deg
  228. // @Range: -180.00 179.99
  229. // @Increment: 1
  230. // @User: Standard
  231. AP_GROUPINFO("2_NEUTRAL", 27, AP_Mount, state[1]._neutral_angles, 0),
  232. // 3 was used for control_angles
  233. // @Param: 2_STAB_ROLL
  234. // @DisplayName: Stabilize Mount2's roll angle
  235. // @Description: enable roll stabilisation relative to Earth
  236. // @Values: 0:Disabled,1:Enabled
  237. // @User: Standard
  238. AP_GROUPINFO("2_STAB_ROLL", 28, AP_Mount, state[1]._stab_roll, 0),
  239. // @Param: 2_STAB_TILT
  240. // @DisplayName: Stabilize Mount2's pitch/tilt angle
  241. // @Description: enable tilt/pitch stabilisation relative to Earth
  242. // @Values: 0:Disabled,1:Enabled
  243. // @User: Standard
  244. AP_GROUPINFO("2_STAB_TILT", 29, AP_Mount, state[1]._stab_tilt, 0),
  245. // @Param: 2_STAB_PAN
  246. // @DisplayName: Stabilize mount2 pan/yaw angle
  247. // @Description: enable pan/yaw stabilisation relative to Earth
  248. // @Values: 0:Disabled,1:Enabled
  249. // @User: Standard
  250. AP_GROUPINFO("2_STAB_PAN", 30, AP_Mount, state[1]._stab_pan, 0),
  251. // @Param: 2_RC_IN_ROLL
  252. // @DisplayName: Mount2's roll RC input channel
  253. // @Description: 0 for none, any other for the RC channel to be used to control roll movements
  254. // @Values: 0:Disabled,5:RC5,6:RC6,7:RC7,8:RC8,9:RC9,10:RC10,11:RC11,12:RC12
  255. // @User: Standard
  256. AP_GROUPINFO("2_RC_IN_ROLL", 31, AP_Mount, state[1]._roll_rc_in, 0),
  257. // @Param: 2_ANGMIN_ROL
  258. // @DisplayName: Mount2's minimum roll angle
  259. // @Description: Mount2's minimum physical roll angular position
  260. // @Units: cdeg
  261. // @Range: -18000 17999
  262. // @Increment: 1
  263. // @User: Standard
  264. AP_GROUPINFO("2_ANGMIN_ROL", 32, AP_Mount, state[1]._roll_angle_min, -4500),
  265. // @Param: 2_ANGMAX_ROL
  266. // @DisplayName: Mount2's maximum roll angle
  267. // @Description: Mount2's maximum physical roll angular position
  268. // @Units: cdeg
  269. // @Range: -18000 17999
  270. // @Increment: 1
  271. // @User: Standard
  272. AP_GROUPINFO("2_ANGMAX_ROL", 33, AP_Mount, state[1]._roll_angle_max, 4500),
  273. // @Param: 2_RC_IN_TILT
  274. // @DisplayName: Mount2's tilt (pitch) RC input channel
  275. // @Description: 0 for none, any other for the RC channel to be used to control tilt (pitch) movements
  276. // @Values: 0:Disabled,5:RC5,6:RC6,7:RC7,8:RC8,9:RC9,10:RC10,11:RC11,12:RC12
  277. // @User: Standard
  278. AP_GROUPINFO("2_RC_IN_TILT", 34, AP_Mount, state[1]._tilt_rc_in, 0),
  279. // @Param: 2_ANGMIN_TIL
  280. // @DisplayName: Mount2's minimum tilt angle
  281. // @Description: Mount2's minimum physical tilt (pitch) angular position
  282. // @Units: cdeg
  283. // @Range: -18000 17999
  284. // @Increment: 1
  285. // @User: Standard
  286. AP_GROUPINFO("2_ANGMIN_TIL", 35, AP_Mount, state[1]._tilt_angle_min, -4500),
  287. // @Param: 2_ANGMAX_TIL
  288. // @DisplayName: Mount2's maximum tilt angle
  289. // @Description: Mount2's maximum physical tilt (pitch) angular position
  290. // @Units: cdeg
  291. // @Range: -18000 17999
  292. // @Increment: 1
  293. // @User: Standard
  294. AP_GROUPINFO("2_ANGMAX_TIL", 36, AP_Mount, state[1]._tilt_angle_max, 4500),
  295. // @Param: 2_RC_IN_PAN
  296. // @DisplayName: Mount2's pan (yaw) RC input channel
  297. // @Description: 0 for none, any other for the RC channel to be used to control pan (yaw) movements
  298. // @Values: 0:Disabled,5:RC5,6:RC6,7:RC7,8:RC8,9:RC9,10:RC10,11:RC11,12:RC12
  299. // @User: Standard
  300. AP_GROUPINFO("2_RC_IN_PAN", 37, AP_Mount, state[1]._pan_rc_in, 0),
  301. // @Param: 2_ANGMIN_PAN
  302. // @DisplayName: Mount2's minimum pan angle
  303. // @Description: Mount2's minimum physical pan (yaw) angular position
  304. // @Units: cdeg
  305. // @Range: -18000 17999
  306. // @Increment: 1
  307. // @User: Standard
  308. AP_GROUPINFO("2_ANGMIN_PAN", 38, AP_Mount, state[1]._pan_angle_min, -4500),
  309. // @Param: 2_ANGMAX_PAN
  310. // @DisplayName: Mount2's maximum pan angle
  311. // @Description: MOunt2's maximum physical pan (yaw) angular position
  312. // @Units: cdeg
  313. // @Range: -18000 17999
  314. // @Increment: 1
  315. // @User: Standard
  316. AP_GROUPINFO("2_ANGMAX_PAN", 39, AP_Mount, state[1]._pan_angle_max, 4500),
  317. // @Param: 2_LEAD_RLL
  318. // @DisplayName: Mount2's Roll stabilization lead time
  319. // @Description: Causes the servo angle output to lead the current angle of the vehicle by some amount of time based on current angular rate, compensating for servo delay. Increase until the servo is responsive but doesn't overshoot. Does nothing with pan stabilization enabled.
  320. // @Units: s
  321. // @Range: 0.0 0.2
  322. // @Increment: .005
  323. // @User: Standard
  324. AP_GROUPINFO("2_LEAD_RLL", 40, AP_Mount, state[1]._roll_stb_lead, 0.0f),
  325. // @Param: 2_LEAD_PTCH
  326. // @DisplayName: Mount2's Pitch stabilization lead time
  327. // @Description: Causes the servo angle output to lead the current angle of the vehicle by some amount of time based on current angular rate. Increase until the servo is responsive but doesn't overshoot. Does nothing with pan stabilization enabled.
  328. // @Units: s
  329. // @Range: 0.0 0.2
  330. // @Increment: .005
  331. // @User: Standard
  332. AP_GROUPINFO("2_LEAD_PTCH", 41, AP_Mount, state[1]._pitch_stb_lead, 0.0f),
  333. // @Param: 2_TYPE
  334. // @DisplayName: Mount2 Type
  335. // @Description: Mount Type (None, Servo or MAVLink)
  336. // @Values: 0:None, 1:Servo, 2:3DR Solo, 3:Alexmos Serial, 4:SToRM32 MAVLink, 5:SToRM32 Serial
  337. // @User: Standard
  338. AP_GROUPINFO("2_TYPE", 42, AP_Mount, state[1]._type, 0),
  339. #endif // AP_MOUNT_MAX_INSTANCES > 1
  340. AP_GROUPEND
  341. };
  342. AP_Mount::AP_Mount(const struct Location &current_loc) :
  343. _current_loc(current_loc)
  344. {
  345. if (_singleton != nullptr) {
  346. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  347. AP_HAL::panic("Mount must be singleton");
  348. #endif
  349. return;
  350. }
  351. _singleton = this;
  352. AP_Param::setup_object_defaults(this, var_info);
  353. }
  354. // init - detect and initialise all mounts
  355. void AP_Mount::init()
  356. {
  357. // check init has not been called before
  358. if (_num_instances != 0) {
  359. return;
  360. }
  361. // default mount to servo mount if rc output channels to control roll, tilt or pan have been defined
  362. if (!state[0]._type.configured()) {
  363. if (SRV_Channels::function_assigned(SRV_Channel::Aux_servo_function_t::k_mount_pan) ||
  364. SRV_Channels::function_assigned(SRV_Channel::Aux_servo_function_t::k_mount_tilt) ||
  365. SRV_Channels::function_assigned(SRV_Channel::Aux_servo_function_t::k_mount_roll)) {
  366. state[0]._type.set_and_save(Mount_Type_Servo);
  367. }
  368. }
  369. // primary is reset to the first instantiated mount
  370. bool primary_set = false;
  371. // create each instance
  372. for (uint8_t instance=0; instance<AP_MOUNT_MAX_INSTANCES; instance++) {
  373. // default instance's state
  374. state[instance]._mode = (enum MAV_MOUNT_MODE)state[instance]._default_mode.get();
  375. MountType mount_type = get_mount_type(instance);
  376. // check for servo mounts
  377. if (mount_type == Mount_Type_Servo) {
  378. _backends[instance] = new AP_Mount_Servo(*this, state[instance], instance);
  379. _num_instances++;
  380. #if AP_AHRS_NAVEKF_AVAILABLE
  381. #if !HAL_MINIMIZE_FEATURES
  382. // check for MAVLink mounts
  383. } else if (mount_type == Mount_Type_SoloGimbal) {
  384. _backends[instance] = new AP_Mount_SoloGimbal(*this, state[instance], instance);
  385. _num_instances++;
  386. #endif // HAL_MINIMIZE_FEATURES
  387. #endif // AP_AHRS_NAVEKF_AVAILABLE
  388. // check for Alexmos mounts
  389. } else if (mount_type == Mount_Type_Alexmos) {
  390. _backends[instance] = new AP_Mount_Alexmos(*this, state[instance], instance);
  391. _num_instances++;
  392. // check for SToRM32 mounts using MAVLink protocol
  393. } else if (mount_type == Mount_Type_SToRM32) {
  394. _backends[instance] = new AP_Mount_SToRM32(*this, state[instance], instance);
  395. _num_instances++;
  396. // check for SToRM32 mounts using serial protocol
  397. } else if (mount_type == Mount_Type_SToRM32_serial) {
  398. _backends[instance] = new AP_Mount_SToRM32_serial(*this, state[instance], instance);
  399. _num_instances++;
  400. }
  401. // init new instance
  402. if (_backends[instance] != nullptr) {
  403. _backends[instance]->init();
  404. if (!primary_set) {
  405. _primary = instance;
  406. primary_set = true;
  407. }
  408. }
  409. }
  410. }
  411. // update - give mount opportunity to update servos. should be called at 10hz or higher
  412. void AP_Mount::update()
  413. {
  414. // update each instance
  415. for (uint8_t instance=0; instance<AP_MOUNT_MAX_INSTANCES; instance++) {
  416. if (_backends[instance] != nullptr) {
  417. _backends[instance]->update();
  418. }
  419. }
  420. }
  421. // used for gimbals that need to read INS data at full rate
  422. void AP_Mount::update_fast()
  423. {
  424. // update each instance
  425. for (uint8_t instance=0; instance<AP_MOUNT_MAX_INSTANCES; instance++) {
  426. if (_backends[instance] != nullptr) {
  427. _backends[instance]->update_fast();
  428. }
  429. }
  430. }
  431. // get_mount_type - returns the type of mount
  432. AP_Mount::MountType AP_Mount::get_mount_type(uint8_t instance) const
  433. {
  434. if (instance >= AP_MOUNT_MAX_INSTANCES) {
  435. return Mount_Type_None;
  436. }
  437. return (MountType)state[instance]._type.get();
  438. }
  439. // has_pan_control - returns true if the mount has yaw control (required for copters)
  440. bool AP_Mount::has_pan_control(uint8_t instance) const
  441. {
  442. if (instance >= AP_MOUNT_MAX_INSTANCES || _backends[instance] == nullptr) {
  443. return false;
  444. }
  445. // ask backend if it support pan
  446. return _backends[instance]->has_pan_control();
  447. }
  448. // get_mode - returns current mode of mount (i.e. Retracted, Neutral, RC_Targeting, GPS Point)
  449. MAV_MOUNT_MODE AP_Mount::get_mode(uint8_t instance) const
  450. {
  451. // sanity check instance
  452. if (instance >= AP_MOUNT_MAX_INSTANCES) {
  453. return MAV_MOUNT_MODE_RETRACT;
  454. }
  455. return state[instance]._mode;
  456. }
  457. // set_mode_to_default - restores the mode to it's default mode held in the MNT_MODE parameter
  458. // this operation requires 60us on a Pixhawk/PX4
  459. void AP_Mount::set_mode_to_default(uint8_t instance)
  460. {
  461. set_mode(instance, (enum MAV_MOUNT_MODE)state[instance]._default_mode.get());
  462. }
  463. // set_mode - sets mount's mode
  464. void AP_Mount::set_mode(uint8_t instance, enum MAV_MOUNT_MODE mode)
  465. {
  466. // sanity check instance
  467. if (instance >= AP_MOUNT_MAX_INSTANCES || _backends[instance] == nullptr) {
  468. return;
  469. }
  470. // call backend's set_mode
  471. _backends[instance]->set_mode(mode);
  472. }
  473. // set_angle_targets - sets angle targets in degrees
  474. void AP_Mount::set_angle_targets(uint8_t instance, float roll, float tilt, float pan)
  475. {
  476. if (instance >= AP_MOUNT_MAX_INSTANCES || _backends[instance] == nullptr) {
  477. return;
  478. }
  479. // send command to backend
  480. _backends[instance]->set_angle_targets(roll, tilt, pan);
  481. }
  482. MAV_RESULT AP_Mount::handle_command_do_mount_configure(const mavlink_command_long_t &packet)
  483. {
  484. if (_primary >= AP_MOUNT_MAX_INSTANCES || _backends[_primary] == nullptr) {
  485. return MAV_RESULT_FAILED;
  486. }
  487. _backends[_primary]->set_mode((MAV_MOUNT_MODE)packet.param1);
  488. state[0]._stab_roll = packet.param2;
  489. state[0]._stab_tilt = packet.param3;
  490. state[0]._stab_pan = packet.param4;
  491. return MAV_RESULT_ACCEPTED;
  492. }
  493. MAV_RESULT AP_Mount::handle_command_do_mount_control(const mavlink_command_long_t &packet)
  494. {
  495. if (_primary >= AP_MOUNT_MAX_INSTANCES || _backends[_primary] == nullptr) {
  496. return MAV_RESULT_FAILED;
  497. }
  498. // send message to backend
  499. _backends[_primary]->control(packet.param1, packet.param2, packet.param3, (MAV_MOUNT_MODE) packet.param7);
  500. return MAV_RESULT_ACCEPTED;
  501. }
  502. MAV_RESULT AP_Mount::handle_command_long(const mavlink_command_long_t &packet)
  503. {
  504. switch (packet.command) {
  505. case MAV_CMD_DO_MOUNT_CONFIGURE:
  506. return handle_command_do_mount_configure(packet);
  507. case MAV_CMD_DO_MOUNT_CONTROL:
  508. return handle_command_do_mount_control(packet);
  509. default:
  510. return MAV_RESULT_UNSUPPORTED;
  511. }
  512. }
  513. /// Change the configuration of the mount
  514. void AP_Mount::handle_mount_configure(const mavlink_message_t &msg)
  515. {
  516. if (_primary >= AP_MOUNT_MAX_INSTANCES || _backends[_primary] == nullptr) {
  517. return;
  518. }
  519. mavlink_mount_configure_t packet;
  520. mavlink_msg_mount_configure_decode(&msg, &packet);
  521. // send message to backend
  522. _backends[_primary]->handle_mount_configure(packet);
  523. }
  524. /// Control the mount (depends on the previously set mount configuration)
  525. void AP_Mount::handle_mount_control(const mavlink_message_t &msg)
  526. {
  527. if (_primary >= AP_MOUNT_MAX_INSTANCES || _backends[_primary] == nullptr) {
  528. return;
  529. }
  530. mavlink_mount_control_t packet;
  531. mavlink_msg_mount_control_decode(&msg, &packet);
  532. // send message to backend
  533. _backends[_primary]->handle_mount_control(packet);
  534. }
  535. /// Return mount status information
  536. void AP_Mount::send_mount_status(mavlink_channel_t chan)
  537. {
  538. // call send_mount_status for each instance
  539. for (uint8_t instance=0; instance<AP_MOUNT_MAX_INSTANCES; instance++) {
  540. if (_backends[instance] != nullptr) {
  541. _backends[instance]->send_mount_status(chan);
  542. }
  543. }
  544. }
  545. // set_roi_target - sets target location that mount should attempt to point towards
  546. void AP_Mount::set_roi_target(uint8_t instance, const struct Location &target_loc)
  547. {
  548. // call instance's set_roi_cmd
  549. if (instance < AP_MOUNT_MAX_INSTANCES && _backends[instance] != nullptr) {
  550. _backends[instance]->set_roi_target(target_loc);
  551. }
  552. }
  553. // pass a GIMBAL_REPORT message to the backend
  554. void AP_Mount::handle_gimbal_report(mavlink_channel_t chan, const mavlink_message_t &msg)
  555. {
  556. for (uint8_t instance=0; instance<AP_MOUNT_MAX_INSTANCES; instance++) {
  557. if (_backends[instance] != nullptr) {
  558. _backends[instance]->handle_gimbal_report(chan, msg);
  559. }
  560. }
  561. }
  562. void AP_Mount::handle_message(mavlink_channel_t chan, const mavlink_message_t &msg)
  563. {
  564. switch (msg.msgid) {
  565. case MAVLINK_MSG_ID_GIMBAL_REPORT:
  566. handle_gimbal_report(chan, msg);
  567. break;
  568. case MAVLINK_MSG_ID_MOUNT_CONFIGURE:
  569. handle_mount_configure(msg);
  570. break;
  571. case MAVLINK_MSG_ID_MOUNT_CONTROL:
  572. handle_mount_control(msg);
  573. break;
  574. default:
  575. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  576. AP_HAL::panic("Unhandled mount case");
  577. #endif
  578. break;
  579. }
  580. }
  581. // handle PARAM_VALUE
  582. void AP_Mount::handle_param_value(const mavlink_message_t &msg)
  583. {
  584. for (uint8_t instance=0; instance<AP_MOUNT_MAX_INSTANCES; instance++) {
  585. if (_backends[instance] != nullptr) {
  586. _backends[instance]->handle_param_value(msg);
  587. }
  588. }
  589. }
  590. // send a GIMBAL_REPORT message to the GCS
  591. void AP_Mount::send_gimbal_report(mavlink_channel_t chan)
  592. {
  593. for (uint8_t instance=0; instance<AP_MOUNT_MAX_INSTANCES; instance++) {
  594. if (_backends[instance] != nullptr) {
  595. _backends[instance]->send_gimbal_report(chan);
  596. }
  597. }
  598. }
  599. // singleton instance
  600. AP_Mount *AP_Mount::_singleton;
  601. namespace AP {
  602. AP_Mount *mount()
  603. {
  604. return AP_Mount::get_singleton();
  605. }
  606. };