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