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