APM:Libraries
AP_Mount_SToRM32_serial.cpp
Go to the documentation of this file.
2 #include <AP_HAL/AP_HAL.h>
4 #include <GCS_MAVLink/include/mavlink/v2.0/checksum.h>
6 
7 extern const AP_HAL::HAL& hal;
8 
10  AP_Mount_Backend(frontend, state, instance),
11  _port(nullptr),
12  _initialised(false),
13  _last_send(0),
14  _reply_length(0),
15  _reply_counter(0),
16  _reply_type(ReplyType_UNKNOWN)
17 {}
18 
19 // init - performs any required initialisation for this instance
21 {
23  if (_port) {
24  _initialised = true;
25  set_mode((enum MAV_MOUNT_MODE)_state._default_mode.get());
26  }
27 
28 }
29 
30 // update mount position - should be called periodically
32 {
33  // exit immediately if not initialised
34  if (!_initialised) {
35  return;
36  }
37 
38  read_incoming(); // read the incoming messages from the gimbal
39 
40  // flag to trigger sending target angles to gimbal
41  bool resend_now = false;
42 
43  // update based on mount mode
44  switch(get_mode()) {
45  // move mount to a "retracted" position. To-Do: remove support and replace with a relaxed mode?
46  case MAV_MOUNT_MODE_RETRACT:
47  {
48  const Vector3f &target = _state._retract_angles.get();
49  _angle_ef_target_rad.x = ToRad(target.x);
50  _angle_ef_target_rad.y = ToRad(target.y);
51  _angle_ef_target_rad.z = ToRad(target.z);
52  }
53  break;
54 
55  // move mount to a neutral position, typically pointing forward
56  case MAV_MOUNT_MODE_NEUTRAL:
57  {
58  const Vector3f &target = _state._neutral_angles.get();
59  _angle_ef_target_rad.x = ToRad(target.x);
60  _angle_ef_target_rad.y = ToRad(target.y);
61  _angle_ef_target_rad.z = ToRad(target.z);
62  }
63  break;
64 
65  // point to the angles given by a mavlink message
66  case MAV_MOUNT_MODE_MAVLINK_TARGETING:
67  // 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
68  break;
69 
70  // RC radio manual angle control, but with stabilization from the AHRS
71  case MAV_MOUNT_MODE_RC_TARGETING:
72  // update targets using pilot's rc inputs
74  resend_now = true;
75  break;
76 
77  // point mount to a GPS point given by the mission planner
78  case MAV_MOUNT_MODE_GPS_POINT:
79  if(AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D) {
81  resend_now = true;
82  }
83  break;
84 
85  default:
86  // we do not know this mode so do nothing
87  break;
88  }
89 
90  // resend target angles at least once per second
91  resend_now = resend_now || ((AP_HAL::millis() - _last_send) > AP_MOUNT_STORM32_SERIAL_RESEND_MS);
92 
95  }
96  if (can_send(resend_now)) {
97  if (resend_now) {
99  get_angles();
101  _reply_counter = 0;
103  } else {
104  get_angles();
106  _reply_counter = 0;
108  }
109  }
110 }
111 
112 // has_pan_control - returns true if this mount can control it's pan (required for multicopters)
114 {
115  // we do not have yaw control
116  return false;
117 }
118 
119 // set_mode - sets mount's mode
120 void AP_Mount_SToRM32_serial::set_mode(enum MAV_MOUNT_MODE mode)
121 {
122  // exit immediately if not initialised
123  if (!_initialised) {
124  return;
125  }
126 
127  // record the mode change
128  _state._mode = mode;
129 }
130 
131 // status_msg - called to allow mounts to send their status to GCS using the MOUNT_STATUS message
133 {
134  // return target angles as gimbal's actual attitude.
135  mavlink_msg_mount_status_send(chan, 0, 0, _current_angle.y, _current_angle.x, _current_angle.z);
136 }
137 
138 bool AP_Mount_SToRM32_serial::can_send(bool with_control) {
139  uint16_t required_tx = 1;
140  if (with_control) {
141  required_tx += sizeof(AP_Mount_SToRM32_serial::cmd_set_angles_struct);
142  }
143  return (_reply_type == ReplyType_UNKNOWN) && (_port->txspace() >= required_tx);
144 }
145 
146 
147 // send_target_angles
148 void AP_Mount_SToRM32_serial::send_target_angles(float pitch_deg, float roll_deg, float yaw_deg)
149 {
150 
151  static cmd_set_angles_struct cmd_set_angles_data = {
152  0xFA,
153  0x0E,
154  0x11,
155  0, // pitch
156  0, // roll
157  0, // yaw
158  0, // flags
159  0, // type
160  0, // crc
161  };
162 
163  // exit immediately if not initialised
164  if (!_initialised) {
165  return;
166  }
167 
168  if ((size_t)_port->txspace() < sizeof(cmd_set_angles_data)) {
169  return;
170  }
171 
172  // reverse pitch and yaw control
173  pitch_deg = -pitch_deg;
174  yaw_deg = -yaw_deg;
175 
176  // send CMD_SETANGLE
177  cmd_set_angles_data.pitch = pitch_deg;
178  cmd_set_angles_data.roll = roll_deg;
179  cmd_set_angles_data.yaw = yaw_deg;
180 
181  uint8_t* buf = (uint8_t*)&cmd_set_angles_data;
182 
183  cmd_set_angles_data.crc = crc_calculate(&buf[1], sizeof(cmd_set_angles_data)-3);
184 
185  for (uint8_t i = 0; i != sizeof(cmd_set_angles_data) ; i++) {
186  _port->write(buf[i]);
187  }
188 
189  // store time of send
191 }
192 
194  // exit immediately if not initialised
195  if (!_initialised) {
196  return;
197  }
198 
199  if (_port->txspace() < 1) {
200  return;
201  }
202 
203  _port->write('d');
204 };
205 
206 
208  switch (reply_type) {
209  case ReplyType_DATA:
210  return sizeof(SToRM32_reply_data_struct);
211  break;
212  case ReplyType_ACK:
213  return sizeof(SToRM32_reply_ack_struct);
214  break;
215  default:
216  return 0;
217  }
218 }
219 
220 
222  uint8_t data;
223  int16_t numc;
224 
225  numc = _port->available();
226 
227  if (numc < 0 ){
228  return;
229  }
230 
231  for (int16_t i = 0; i < numc; i++) { // Process bytes received
232  data = _port->read();
234  continue;
235  }
236 
237  _buffer[_reply_counter++] = data;
238  if (_reply_counter == _reply_length) {
239  parse_reply();
240 
241  switch (_reply_type) {
242  case ReplyType_ACK:
245  _reply_counter = 0;
246  break;
247  case ReplyType_DATA:
250  _reply_counter = 0;
251  break;
252  default:
254  _reply_counter = 0;
255  break;
256  }
257  }
258  }
259 }
260 
262  uint16_t crc;
263  bool crc_ok;
264 
265  switch (_reply_type) {
266  case ReplyType_DATA:
267  crc = crc_calculate(&_buffer[0], sizeof(_buffer.data) - 3);
268  crc_ok = crc == _buffer.data.crc;
269  if (!crc_ok) {
270  break;
271  }
272 
276  break;
277  case ReplyType_ACK:
278  crc = crc_calculate(&_buffer[1],
279  sizeof(SToRM32_reply_ack_struct) - 3);
280  crc_ok = crc == _buffer.ack.crc;
281  break;
282  default:
283  break;
284  }
285 }
MAV_MOUNT_MODE _mode
Definition: AP_Mount.h:182
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
virtual void init(const AP_SerialManager &serial_manager)
Vector3f _angle_ef_target_rad
union PACKED AP_Mount_SToRM32_serial::SToRM32_reply _buffer
#define ToRad(x)
Definition: AP_Common.h:53
uint8_t get_reply_size(ReplyType reply_type)
bool can_send(bool with_control)
virtual uint32_t txspace()=0
AP_Mount::mount_state & _state
#define ToDeg(x)
Definition: AP_Common.h:54
void send_target_angles(float pitch_deg, float roll_deg, float yaw_deg)
virtual void status_msg(mavlink_channel_t chan)
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
uint32_t millis()
Definition: system.cpp:157
struct Location _roi_target
Definition: AP_Mount.h:183
AP_Vector3f _retract_angles
Definition: AP_Mount.h:176
T z
Definition: vector3.h:67
static int state
Definition: Util.cpp:20
Receiving valid messages and 2D lock.
Definition: AP_GPS.h:99
virtual int16_t read()=0
virtual bool has_pan_control() const
AP_Vector3f _neutral_angles
Definition: AP_Mount.h:177
virtual uint32_t available()=0
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
DEFINE_BYTE_ARRAY_METHODS SToRM32_reply_data_struct data
AP_Mount_SToRM32_serial(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance)
#define AP_MOUNT_STORM32_SERIAL_RESEND_MS
AP_GPS & gps()
Definition: AP_GPS.cpp:1550
virtual void set_mode(enum MAV_MOUNT_MODE mode)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
MAV_MOUNT_MODE get_mode(void) const
T x
Definition: vector3.h:67
AP_HAL::UARTDriver * find_serial(enum SerialProtocol protocol, uint8_t instance) const