APM:Libraries
AP_Mount_Alexmos.cpp
Go to the documentation of this file.
1 #include "AP_Mount_Alexmos.h"
2 
3 extern const AP_HAL::HAL& hal;
4 
6 {
7  // check for alexmos protcol
9  _initialised = true;
10  get_boardinfo();
11  read_params(0); //we request parameters for profile 0 and therfore get global and profile parameters
12  }
13 }
14 
15 // update mount position - should be called periodically
17 {
18  if (!_initialised) {
19  return;
20  }
21 
22  read_incoming(); // read the incoming messages from the gimbal
23 
24  // update based on mount mode
25  switch(get_mode()) {
26  // move mount to a "retracted" position. we do not implement a separate servo based retract mechanism
27  case MAV_MOUNT_MODE_RETRACT:
28  control_axis(_state._retract_angles.get(), true);
29  break;
30 
31  // move mount to a neutral position, typically pointing forward
32  case MAV_MOUNT_MODE_NEUTRAL:
33  control_axis(_state._neutral_angles.get(), true);
34  break;
35 
36  // point to the angles given by a mavlink message
37  case MAV_MOUNT_MODE_MAVLINK_TARGETING:
38  // do nothing because earth-frame angle targets (i.e. _angle_ef_target_rad) should have already been set by a MOUNT_CONTROL message from GCS
40  break;
41 
42  // RC radio manual angle control, but with stabilization from the AHRS
43  case MAV_MOUNT_MODE_RC_TARGETING:
44  // update targets using pilot's rc inputs
47  break;
48 
49  // point mount to a GPS point given by the mission planner
50  case MAV_MOUNT_MODE_GPS_POINT:
51  if(AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D) {
54  }
55  break;
56 
57  default:
58  // we do not know this mode so do nothing
59  break;
60  }
61 }
62 
63 // has_pan_control - returns true if this mount can control it's pan (required for multicopters)
65 {
66  return _gimbal_3axis;
67 }
68 
69 // set_mode - sets mount's mode
70 void AP_Mount_Alexmos::set_mode(enum MAV_MOUNT_MODE mode)
71 {
72  // record the mode change and return success
73  _state._mode = mode;
74 }
75 
76 // status_msg - called to allow mounts to send their status to GCS using the MOUNT_STATUS message
77 void AP_Mount_Alexmos::status_msg(mavlink_channel_t chan)
78 {
79  if (!_initialised) {
80  return;
81  }
82 
83  get_angles();
84  mavlink_msg_mount_status_send(chan, 0, 0, _current_angle.y*100, _current_angle.x*100, _current_angle.z*100);
85 }
86 
87 /*
88  * get_angles
89  */
91 {
92  uint8_t data[1] = {(uint8_t)1};
93  send_command(CMD_GET_ANGLES, data, 1);
94 }
95 
96 /*
97  * set_motor will activate motors if true, and disable them if false.
98  */
100 {
101  if (on) {
102  uint8_t data[1] = {(uint8_t)1};
103  send_command(CMD_MOTORS_ON, data, 1);
104  } else {
105  uint8_t data[1] = {(uint8_t)1};
106  send_command(CMD_MOTORS_OFF, data, 1);
107  }
108 }
109 
110 /*
111  * get board version and firmware version
112  */
114 {
115  if (_board_version != 0) {
116  return;
117  }
118  uint8_t data[1] = {(uint8_t)1};
119  send_command(CMD_BOARD_INFO, data, 1);
120 }
121 
122 /*
123  control_axis : send new angles to the gimbal at a fixed speed of 30 deg/s2
124 */
125 void AP_Mount_Alexmos::control_axis(const Vector3f& angle, bool target_in_degrees)
126 {
127  // convert to degrees if necessary
128  Vector3f target_deg = angle;
129  if (!target_in_degrees) {
130  target_deg *= RAD_TO_DEG;
131  }
132  alexmos_parameters outgoing_buffer;
133  outgoing_buffer.angle_speed.mode = AP_MOUNT_ALEXMOS_MODE_ANGLE;
135  outgoing_buffer.angle_speed.angle_roll = DEGREE_TO_VALUE(target_deg.x);
137  outgoing_buffer.angle_speed.angle_pitch = DEGREE_TO_VALUE(target_deg.y);
139  outgoing_buffer.angle_speed.angle_yaw = DEGREE_TO_VALUE(target_deg.z);
140  send_command(CMD_CONTROL, (uint8_t *)&outgoing_buffer.angle_speed, sizeof(alexmos_angles_speed));
141 }
142 
143 /*
144  read current profile profile_id and global parameters from the gimbal settings
145 */
146 void AP_Mount_Alexmos::read_params(uint8_t profile_id)
147 {
148  uint8_t data[1] = {(uint8_t) profile_id};
149  send_command(CMD_READ_PARAMS, data, 1);
150 }
151 
152 /*
153  write new parameters to the gimbal settings
154 */
156 {
157  if (!_param_read_once) {
158  return;
159  }
161 }
162 
163 /*
164  send a command to the Alemox Serial API
165 */
166 void AP_Mount_Alexmos::send_command(uint8_t cmd, uint8_t* data, uint8_t size)
167 {
168  if (_port->txspace() < (size + 5U)) {
169  return;
170  }
171  uint8_t checksum = 0;
172  _port->write( '>' );
173  _port->write( cmd ); // write command id
174  _port->write( size ); // write body size
175  _port->write( cmd+size ); // write header checkum
176 
177  for (uint8_t i = 0; i != size ; i++) {
178  checksum += data[i];
179  _port->write( data[i] );
180  }
181  _port->write(checksum);
182 }
183 
184 /*
185  * Parse the body of the message received from the Alexmos gimbal
186  */
188 {
189  switch (_command_id ) {
190  case CMD_BOARD_INFO:
196  break;
197 
198  case CMD_GET_ANGLES:
202  break;
203 
204  case CMD_READ_PARAMS:
205  _param_read_once = true;
207  break;
208 
209  case CMD_WRITE_PARAMS:
210  break;
211 
212  default :
214  break;
215  }
216 }
217 
218 /*
219  * detect and read the header of the incoming message from the gimbal
220  */
222 {
223  uint8_t data;
224  int16_t numc;
225 
226  numc = _port->available();
227 
228  if (numc < 0 ){
229  return;
230  }
231 
232  for (int16_t i = 0; i < numc; i++) { // Process bytes received
233  data = _port->read();
234  switch (_step) {
235  case 0:
236  if ( '>' == data) {
237  _step = 1;
238  _checksum = 0; //reset checksum accumulator
239  _last_command_confirmed = false;
240  }
241  break;
242 
243  case 1: // command ID
244  _checksum = data;
245  _command_id = data;
246  _step++;
247  break;
248 
249  case 2: // Size of the body of the message
250  _checksum += data;
251  _payload_length = data;
252  _step++;
253  break;
254 
255  case 3: // checksum of the header
256  if (_checksum != data ) {
257  _step = 0;
258  _checksum = 0;
259  // checksum error
260  break;
261  }
262  _step++;
263  _checksum = 0;
264  _payload_counter = 0; // prepare to receive payload
265  break;
266 
267  case 4: // parsing body
268  _checksum += data;
269  if (_payload_counter < sizeof(_buffer)) {
270  _buffer[_payload_counter] = data;
271  }
273  _step++;
274  break;
275 
276  case 5:// body checksum
277  _step = 0;
278  if (_checksum != data) {
279  break;
280  }
281  parse_body();
282  }
283  }
284 }
uint8_t _firmware_beta_version
MAV_MOUNT_MODE _mode
Definition: AP_Mount.h:182
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
Vector3f _angle_ef_target_rad
#define on
Definition: Config.h:51
AP_HAL::UARTDriver * _port
#define CMD_BOARD_INFO
virtual uint32_t txspace()=0
AP_Mount::mount_state & _state
#define CMD_WRITE_PARAMS
void send_command(uint8_t cmd, uint8_t *data, uint8_t size)
union PACKED AP_Mount_Alexmos::alexmos_parameters _buffer
#define CMD_MOTORS_OFF
#define CMD_GET_ANGLES
#define AP_MOUNT_ALEXMOS_SPEED
virtual bool has_pan_control() const
union PACKED AP_Mount_Alexmos::alexmos_parameters _current_parameters
void calc_angle_to_location(const struct Location &target, Vector3f &angles_to_target_rad, bool calc_tilt, bool calc_pan, bool relative_pan=true)
T y
Definition: vector3.h:67
virtual size_t write(uint8_t)=0
virtual void status_msg(mavlink_channel_t chan)
#define AP_MOUNT_ALEXMOS_MODE_ANGLE
virtual void set_mode(enum MAV_MOUNT_MODE mode)
#define RAD_TO_DEG
Definition: definitions.h:31
struct Location _roi_target
Definition: AP_Mount.h:183
AP_Vector3f _retract_angles
Definition: AP_Mount.h:176
T z
Definition: vector3.h:67
void control_axis(const Vector3f &angle, bool targets_in_degrees)
void read_params(uint8_t profile_id)
#define VALUE_TO_DEGREE(d)
Receiving valid messages and 2D lock.
Definition: AP_GPS.h:99
virtual int16_t read()=0
AP_Vector3f _neutral_angles
Definition: AP_Mount.h:177
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
virtual uint32_t available()=0
#define CMD_CONTROL
virtual void update()
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
#define CMD_MOTORS_ON
#define CMD_READ_PARAMS
AP_GPS & gps()
Definition: AP_GPS.cpp:1550
#define DEGREE_TO_VALUE(d)
#define DEGREE_PER_SEC_TO_VALUE(d)
MAV_MOUNT_MODE get_mode(void) const
DEFINE_BYTE_ARRAY_METHODS alexmos_version version
void set_motor(bool on)
T x
Definition: vector3.h:67
AP_HAL::UARTDriver * find_serial(enum SerialProtocol protocol, uint8_t instance) const
virtual void init(const AP_SerialManager &serial_manager)