APM:Libraries
AP_Mount.h
Go to the documentation of this file.
1 /************************************************************
2 * AP_mount -- library to control a 2 or 3 axis mount. *
3 * *
4 * Author: Joe Holdsworth; *
5 * Ritchie Wilson; *
6 * Amilcar Lucas; *
7 * Gregory Fletcher; *
8 * heavily modified by Randy Mackay *
9 * *
10 * Purpose: Move a 2 or 3 axis mount attached to vehicle, *
11 * Used for mount to track targets or stabilise *
12 * camera plus other modes. *
13 * *
14 * Usage: Use in main code to control mounts attached to *
15 * vehicle. *
16 * *
17 * Comments: All angles in degrees * 100, distances in meters*
18 * unless otherwise stated. *
19 ************************************************************/
20 #pragma once
21 
22 #include <AP_Math/AP_Math.h>
23 #include <AP_Common/AP_Common.h>
24 #include <AP_GPS/AP_GPS.h>
25 #include <AP_AHRS/AP_AHRS.h>
27 #include <RC_Channel/RC_Channel.h>
29 #include <DataFlash/DataFlash.h>
30 
31 // maximum number of mounts
32 #define AP_MOUNT_MAX_INSTANCES 1
33 
34 // declare backend classes
35 class AP_Mount_Backend;
36 class AP_Mount_Servo;
37 class AP_Mount_SoloGimbal;
38 class AP_Mount_Alexmos;
39 class AP_Mount_SToRM32;
41 
42 /*
43  This is a workaround to allow the MAVLink backend access to the
44  SmallEKF. It would be nice to find a neater solution to this
45  */
46 
47 class AP_Mount
48 {
49  // declare backends as friends
50  friend class AP_Mount_Backend;
51  friend class AP_Mount_Servo;
52  friend class AP_Mount_SoloGimbal;
53  friend class AP_Mount_Alexmos;
54  friend class AP_Mount_SToRM32;
56 
57 public:
58  AP_Mount(const AP_AHRS_TYPE &ahrs, const struct Location &current_loc);
59 
60  /* Do not allow copies */
61  AP_Mount(const AP_Mount &other) = delete;
62  AP_Mount &operator=(const AP_Mount&) = delete;
63 
64 
65  // Enums
66  enum MountType {
73  };
74 
75  // init - detect and initialise all mounts
77 
78  // update - give mount opportunity to update servos. should be called at 10hz or higher
79  void update();
80 
81  // used for gimbals that need to read INS data at full rate
82  void update_fast();
83 
84  // get_mount_type - returns the type of mount
86  AP_Mount::MountType get_mount_type(uint8_t instance) const;
87 
88  // has_pan_control - returns true if the mount has yaw control (required for copters)
89  bool has_pan_control() const { return has_pan_control(_primary); }
90  bool has_pan_control(uint8_t instance) const;
91 
92  // get_mode - returns current mode of mount (i.e. Retracted, Neutral, RC_Targeting, GPS Point)
93  enum MAV_MOUNT_MODE get_mode() const { return get_mode(_primary); }
94  enum MAV_MOUNT_MODE get_mode(uint8_t instance) const;
95 
96  // set_mode - sets mount's mode
97  // returns true if mode is successfully set
98  void set_mode(enum MAV_MOUNT_MODE mode) { return set_mode(_primary, mode); }
99  void set_mode(uint8_t instance, enum MAV_MOUNT_MODE mode);
100 
101  // set_mode_to_default - restores the mode to it's default mode held in the MNT_DEFLT_MODE parameter
102  // this operation requires 60us on a Pixhawk/PX4
104  void set_mode_to_default(uint8_t instance);
105 
106  // set_angle_targets - sets angle targets in degrees
107  void set_angle_targets(float roll, float tilt, float pan) { set_angle_targets(_primary, roll, tilt, pan); }
108  void set_angle_targets(uint8_t instance, float roll, float tilt, float pan);
109 
110  // set_roi_target - sets target location that mount should attempt to point towards
111  void set_roi_target(const struct Location &target_loc) { set_roi_target(_primary,target_loc); }
112  void set_roi_target(uint8_t instance, const struct Location &target_loc);
113 
114  // control - control the mount
115  void control(int32_t pitch_or_lat, int32_t roll_or_lon, int32_t yaw_or_alt, enum MAV_MOUNT_MODE mount_mode) { control(_primary, pitch_or_lat, roll_or_lon, yaw_or_alt, mount_mode); }
116  void 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);
117 
118  // configure_msg - process MOUNT_CONFIGURE messages received from GCS
119  void configure_msg(mavlink_message_t* msg) { configure_msg(_primary, msg); }
120  void configure_msg(uint8_t instance, mavlink_message_t* msg);
121 
122  // control_msg - process MOUNT_CONTROL messages received from GCS
123  void control_msg(mavlink_message_t* msg) { control_msg(_primary, msg); }
124  void control_msg(uint8_t instance, mavlink_message_t* msg);
125 
126  // handle a PARAM_VALUE message
127  void handle_param_value(mavlink_message_t *msg);
128 
129  // handle a GIMBAL_REPORT message
130  void handle_gimbal_report(mavlink_channel_t chan, mavlink_message_t *msg);
131 
132  // send a GIMBAL_REPORT message to GCS
133  void send_gimbal_report(mavlink_channel_t chan);
134 
135  // status_msg - called to allow mounts to send their status to GCS using the MOUNT_STATUS message
136  void status_msg(mavlink_channel_t chan);
137 
138  // parameter var table
139  static const struct AP_Param::GroupInfo var_info[];
140 
141 protected:
142  // private members
144  const struct Location &_current_loc; // reference to the vehicle's current location
145 
146  // frontend parameters
147  AP_Int8 _joystick_speed; // joystick gain
148 
149  // front end members
150  uint8_t _num_instances; // number of mounts instantiated
151  uint8_t _primary; // primary mount
152  AP_Mount_Backend *_backends[AP_MOUNT_MAX_INSTANCES]; // pointers to instantiated mounts
153 
154  // backend state including parameters
155  struct mount_state {
156  // Parameters
157  AP_Int8 _type; // mount type (None, Servo or MAVLink, see MountType enum)
158  AP_Int8 _default_mode; // default mode on startup and when control is returned from autopilot
159  AP_Int8 _stab_roll; // 1 = mount should stabilize earth-frame roll axis, 0 = no stabilization
160  AP_Int8 _stab_tilt; // 1 = mount should stabilize earth-frame pitch axis
161  AP_Int8 _stab_pan; // 1 = mount should stabilize earth-frame yaw axis
162 
163  // RC input channels from receiver used for direct angular input from pilot
164  AP_Int8 _roll_rc_in; // pilot provides roll input on this channel
165  AP_Int8 _tilt_rc_in; // pilot provides tilt input on this channel
166  AP_Int8 _pan_rc_in; // pilot provides pan input on this channel
167 
168  // Mount's physical limits
169  AP_Int16 _roll_angle_min; // min roll in 0.01 degree units
170  AP_Int16 _roll_angle_max; // max roll in 0.01 degree units
171  AP_Int16 _tilt_angle_min; // min tilt in 0.01 degree units
172  AP_Int16 _tilt_angle_max; // max tilt in 0.01 degree units
173  AP_Int16 _pan_angle_min; // min pan in 0.01 degree units
174  AP_Int16 _pan_angle_max; // max pan in 0.01 degree units
175 
176  AP_Vector3f _retract_angles; // retracted position for mount, vector.x = roll vector.y = tilt, vector.z=pan
177  AP_Vector3f _neutral_angles; // neutral position for mount, vector.x = roll vector.y = tilt, vector.z=pan
178 
179  AP_Float _roll_stb_lead; // roll lead control gain
180  AP_Float _pitch_stb_lead; // pitch lead control gain
181 
182  MAV_MOUNT_MODE _mode; // current mode (see MAV_MOUNT_MODE enum)
183  struct Location _roi_target; // roi target location
185 };
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
AP_Int16 _pan_angle_max
Definition: AP_Mount.h:174
void set_roi_target(const struct Location &target_loc)
Definition: AP_Mount.h:111
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
AP_Int8 _joystick_speed
Definition: AP_Mount.h:147
Solo&#39;s gimbal.
Definition: AP_Mount.h:70
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
#define AP_MOUNT_MAX_INSTANCES
Definition: AP_Mount.h:32
void update()
Definition: AP_Mount.cpp:479
#define AP_AHRS_TYPE
Definition: AP_AHRS.h:682
void send_gimbal_report(mavlink_channel_t chan)
Definition: AP_Mount.cpp:637
SToRM32 mount using MAVLink protocol.
Definition: AP_Mount.h:72
friend class AP_Mount_SoloGimbal
Definition: AP_Mount.h:52
servo controlled mount
Definition: AP_Mount.h:69
RC_Channel manager, with EEPROM-backed storage of constants.
AP_Float _pitch_stb_lead
Definition: AP_Mount.h:180
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
struct Location _roi_target
Definition: AP_Mount.h:183
AP_Vector3f _retract_angles
Definition: AP_Mount.h:176
AP_Mount_Backend * _backends[AP_MOUNT_MAX_INSTANCES]
Definition: AP_Mount.h:152
AP_Vector3f _neutral_angles
Definition: AP_Mount.h:177
AP_Mount & operator=(const AP_Mount &)=delete
Common definitions and utility routines for the ArduPilot libraries.
const AP_AHRS_TYPE & _ahrs
Definition: AP_Mount.h:143
AP_Int16 _pan_angle_min
Definition: AP_Mount.h:173
AP_Int16 _roll_angle_max
Definition: AP_Mount.h:170
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
AP_Int16 _roll_angle_min
Definition: AP_Mount.h:169
struct AP_Mount::mount_state state[AP_MOUNT_MAX_INSTANCES]
AP_Mount::MountType get_mount_type() const
Definition: AP_Mount.h:85
const struct Location & _current_loc
Definition: AP_Mount.h:144
void set_mode_to_default()
Definition: AP_Mount.h:103
AP_Float _roll_stb_lead
Definition: AP_Mount.h:179
uint8_t _primary
Definition: AP_Mount.h:151
AP_Int16 _tilt_angle_max
Definition: AP_Mount.h:172
void handle_gimbal_report(mavlink_channel_t chan, mavlink_message_t *msg)
Definition: AP_Mount.cpp:617
void update_fast()
Definition: AP_Mount.cpp:490
AP_Int16 _tilt_angle_min
Definition: AP_Mount.h:171