APM:Libraries
AP_Beacon_Marvelmind.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 /*
16  Original C Code by Marvelmind (https://github.com/MarvelmindRobotics/marvelmind.c)
17  Adapted into Ardupilot by Karthik Desai, Amilcar Lucas
18  April 2017
19  */
20 
21 #include <AP_HAL/AP_HAL.h>
22 
23 #include "AP_Beacon_Marvelmind.h"
24 
25 #define AP_BEACON_MARVELMIND_POSITION_DATAGRAM_ID 0x0001
26 #define AP_BEACON_MARVELMIND_POSITIONS_DATAGRAM_ID 0x0002
27 #define AP_BEACON_MARVELMIND_DISTANCES_DATAGRAM_ID 0x0004
28 #define AP_BEACON_MARVELMIND_POSITION_DATAGRAM_HIGHRES_ID 0x0011
29 #define AP_BEACON_MARVELMIND_POSITIONS_DATAGRAM_HIGHRES_ID 0x0012
30 
31 extern const AP_HAL::HAL& hal;
32 
33 #define MM_DEBUG_LEVEL 0
34 
35 #if MM_DEBUG_LEVEL
36  #include <GCS_MAVLink/GCS.h>
37  #define Debug(level, fmt, args ...) do { if (level <= MM_DEBUG_LEVEL) { gcs().send_text(MAV_SEVERITY_INFO, fmt, ## args); } } while (0)
38 #else
39  #define Debug(level, fmt, args ...)
40 #endif
41 
43  AP_Beacon_Backend(frontend)
44 {
46  if (uart != nullptr) {
48  last_update_ms = 0;
49  parse_state = RECV_HDR; // current state of receive data
50  num_bytes_in_block_received = 0; // bytes received
51  data_id = 0;
52  hedge._have_new_values = false;
55 
56  }
57 }
58 
60 // Calculate Modbus CRC16 for array of bytes
61 // buf: input buffer
62 // len: size of buffer
63 // returncode: CRC value
65 uint16_t AP_Beacon_Marvelmind::calc_crc_modbus(uint8_t *buf, uint16_t len)
66 {
67  uint16_t crc = 0xFFFF;
68  for (uint16_t pos = 0; pos < len; pos++) {
69  crc ^= (uint16_t) buf[pos]; // XOR byte into least sig. byte of crc
70  for (uint8_t i = 8; i != 0; i--) { // Loop over each bit
71  if ((crc & 0x0001) != 0) { // If the LSB is set
72  crc >>= 1; // Shift right and XOR 0xA001
73  crc ^= 0xA001;
74  } else {
75  // Else LSB is not set
76  crc >>= 1; // Just shift right
77  }
78  }
79  }
80  return crc;
81 }
82 
84 {
87  | (((uint32_t) input_buffer[6]) << 8)
88  | (((uint32_t) input_buffer[7]) << 16)
89  | (((uint32_t) input_buffer[8]) << 24);
90  const int16_t vx = input_buffer[9] | (((uint16_t) input_buffer[10]) << 8);
91  hedge.cur_position.x__mm = vx * 10; // centimeters -> millimeters
92  const int16_t vy = input_buffer[11] | (((uint16_t) input_buffer[12]) << 8);
93  hedge.cur_position.y__mm = vy * 10; // centimeters -> millimeters
94  const int16_t vz = input_buffer[13] | (((uint16_t) input_buffer[14]) << 8);
95  hedge.cur_position.z__mm = vz * 10; // centimeters -> millimeters
97  hedge._have_new_values = true;
98 }
99 
101 {
104  | (((uint32_t) input_buffer[6]) << 8)
105  | (((uint32_t) input_buffer[7]) << 16)
106  | (((uint32_t) input_buffer[8]) << 24);
107  hedge.cur_position.x__mm = input_buffer[9] | (((uint32_t) input_buffer[10]) << 8)
108  | (((uint32_t) input_buffer[11]) << 16)
109  | (((uint32_t) input_buffer[12]) << 24);
110  hedge.cur_position.y__mm = input_buffer[13] | (((uint32_t) input_buffer[14]) << 8)
111  | (((uint32_t) input_buffer[15]) << 16)
112  | (((uint32_t) input_buffer[16]) << 24);
113  hedge.cur_position.z__mm = input_buffer[17] | (((uint32_t) input_buffer[18]) << 8)
114  | (((uint32_t) input_buffer[19]) << 16)
115  | (((uint32_t) input_buffer[20]) << 24);
117  hedge._have_new_values = true;
118 }
119 
121 {
122  const uint8_t n_used = hedge.positions_beacons.num_beacons;
123  for (uint8_t i = 0; i < n_used; i++) {
124  if (hedge.positions_beacons.beacons[i].address == address) {
125  return &hedge.positions_beacons.beacons[i];
126  }
127  }
128  if (n_used >= AP_BEACON_MAX_BEACONS) {
129  return nullptr;
130  }
131  hedge.positions_beacons.num_beacons = (n_used + 1);
132  return &hedge.positions_beacons.beacons[n_used];
133 }
134 
136 {
137  const uint8_t n = input_buffer[5]; // number of beacons in packet
138  StationaryBeaconPosition *stationary_beacon;
139  if ((1 + n * 8) != input_buffer[4]) {
140  Debug(1, "beacon pos lo pkt size %d != %d", input_buffer[4], (1 + n * 8));
141  return; // incorrect size
142  }
143  for (uint8_t i = 0; i < n; i++) {
144  const uint8_t ofs = 6 + i * 8;
145  const uint8_t address = input_buffer[ofs];
146  const int16_t x = input_buffer[ofs + 1]
147  | (((uint16_t) input_buffer[ofs + 2]) << 8);
148  const int16_t y = input_buffer[ofs + 3]
149  | (((uint16_t) input_buffer[ofs + 4]) << 8);
150  const int16_t z = input_buffer[ofs + 5]
151  | (((uint16_t) input_buffer[ofs + 6]) << 8);
152  stationary_beacon = get_or_alloc_beacon(address);
153  if (stationary_beacon != nullptr) {
154  stationary_beacon->address = address; //The instance and the address are the same
155  stationary_beacon->x__mm = x * 10; // centimeters -> millimeters
156  stationary_beacon->y__mm = y * 10; // centimeters -> millimeters
157  stationary_beacon->z__mm = z * 10; // centimeters -> millimeters
158  stationary_beacon->high_resolution = false;
160  }
161  }
163 }
164 
166 {
167  const uint8_t n = input_buffer[5]; // number of beacons in packet
168  StationaryBeaconPosition *stationary_beacon;
169  if ((1 + n * 14) != input_buffer[4]) {
170  Debug(1, "beacon pos hi pkt size %d != %d", input_buffer[4], (1 + n * 14));
171  return; // incorrect size
172  }
173  for (uint8_t i = 0; i < n; i++) {
174  const uint8_t ofs = 6 + i * 14;
175  const uint8_t address = input_buffer[ofs];
176  const int32_t x = input_buffer[ofs + 1]
177  | (((uint32_t) input_buffer[ofs + 2]) << 8)
178  | (((uint32_t) input_buffer[ofs + 3]) << 16)
179  | (((uint32_t) input_buffer[ofs + 4]) << 24);
180  const int32_t y = input_buffer[ofs + 5]
181  | (((uint32_t) input_buffer[ofs + 6]) << 8)
182  | (((uint32_t) input_buffer[ofs + 7]) << 16)
183  | (((uint32_t) input_buffer[ofs + 8]) << 24);
184  const int32_t z = input_buffer[ofs + 9]
185  | (((uint32_t) input_buffer[ofs + 10]) << 8)
186  | (((uint32_t) input_buffer[ofs + 11]) << 16)
187  | (((uint32_t) input_buffer[ofs + 12]) << 24);
188  stationary_beacon = get_or_alloc_beacon(address);
189  if (stationary_beacon != nullptr) {
190  stationary_beacon->address = address; //The instance and the address are the same
191  stationary_beacon->x__mm = x; // millimeters
192  stationary_beacon->y__mm = y; // millimeters
193  stationary_beacon->z__mm = z; // millimeters
194  stationary_beacon->high_resolution = true;
196  }
197  }
199 }
200 
202 {
203  if (32 != input_buffer[4]) {
204  Debug(1, "beacon dist pkt size %d != 32", input_buffer[4]);
205  return; // incorrect size
206  }
207  bool set = false;
208  for (uint8_t i = 0; i < hedge.positions_beacons.num_beacons; i++) {
209  const uint8_t ofs = 6 + i * 6;
210  const uint8_t address = input_buffer[ofs];
211  const int8_t instance = find_beacon_instance(address);
212  if (instance != -1) {
213  const uint32_t distance = input_buffer[ofs + 1]
214  | (((uint32_t) input_buffer[ofs + 2]) << 8)
215  | (((uint32_t) input_buffer[ofs + 3]) << 16)
216  | (((uint32_t) input_buffer[ofs + 4]) << 24);
217  hedge.positions_beacons.beacons[instance].distance__m = distance * 0.001f; // millimeters -> meters
219  set = true;
220  Debug(2, "Beacon %d is %.2fm", instance, hedge.positions_beacons.beacons[instance].distance__m);
221  }
222  }
223  if (set) {
225  }
226 }
227 
228 int8_t AP_Beacon_Marvelmind::find_beacon_instance(uint8_t address) const
229 {
230  for (uint8_t i = 0; i < hedge.positions_beacons.num_beacons; i++) {
231  if (hedge.positions_beacons.beacons[i].address == address) {
232  return i;
233  }
234  }
235  return -1;
236 }
237 
239 {
240  if (uart == nullptr) {
241  return;
242  }
243  // read any available characters
244  int32_t num_bytes_read = uart->available();
245  uint8_t received_char = 0;
246  if (num_bytes_read < 0) {
247  return;
248  }
249  while (num_bytes_read-- > 0) {
250  bool good_byte = false;
251  received_char = uart->read();
252  input_buffer[num_bytes_in_block_received] = received_char;
253  switch (parse_state) {
254  case RECV_HDR:
255  switch (num_bytes_in_block_received) {
256  case 0:
257  good_byte = (received_char == 0xff);
258  break;
259  case 1:
260  good_byte = (received_char == 0x47);
261  break;
262  case 2:
263  good_byte = true;
264  break;
265  case 3:
266  data_id = (((uint16_t)received_char) << 8) + input_buffer[2];
272  break;
273  case 4: {
274  switch (data_id) {
276  good_byte = (received_char == 0x10);
277  break;
278  }
282  good_byte = true;
283  break;
285  good_byte = (received_char == 0x16);
286  break;
287  }
288  }
289  if (good_byte) {
291  }
292  break;
293  }
294  }
295  if (good_byte) {
296  // correct header byte
298  } else {
299  // ...or incorrect
302  }
303  break;
304 
305  case RECV_DGRAM:
308  // parse dgram
310  if (block_crc == 0) {
311  switch (data_id) {
313  {
314  // add to position_buffer
318  break;
319  }
320 
322  {
326  break;
327  }
328 
330  {
332  break;
333  }
334 
336  {
340  break;
341  }
342 
344  {
348  break;
349  }
350  }
351  }
352  // and repeat
355  }
356  break;
357  }
358  }
359 }
360 
362 {
363  // healthy if we have parsed a message within the past 300ms
365 }
366 
368 {
369  bool set = false;
371  if (hedge._have_new_values) {
373  hedge.cur_position.x__mm * 0.001f,
374  -hedge.cur_position.z__mm * 0.001f); //Transform Marvelmind ENU to Ardupilot NED
375  //TODO: Calculate Accuracy of the received signal. Marvelmind *advertises* +/- 2cms
376  // But we are conservative here and use 20cm instead (until MM provides us with a proper accuracy value)
378  set = true;
379  Debug(2,
380  "Hedge is at N%.2f, E%.2f, D%.2f",
384  }
385  hedge._have_new_values = false;
386  for (uint8_t i = 0; i < hedge.positions_beacons.num_beacons; ++i) {
389  hedge.positions_beacons.beacons[i].x__mm * 0.001f,
390  -hedge.positions_beacons.beacons[i].z__mm * 0.001f); //Transform Marvelmind ENU to Ardupilot NED
392  set = true;
393  Debug(2,
394  "Beacon %d is at N%.2f, E%.2f, D%.2f",
395  i,
398  beacon_position_NED__m[i][2]);
399  }
400  }
402 
403  }
404  if (set) {
406  }
407 }
408 
410 {
412  bool swapped = false;
413  uint8_t j = hedge.positions_beacons.num_beacons;
414  do
415  {
416  swapped = false;
417  StationaryBeaconPosition beacon_to_swap;
418  for (uint8_t i = 1; i < j; i++) {
420  beacon_to_swap = hedge.positions_beacons.beacons[i];
422  hedge.positions_beacons.beacons[i-1] = beacon_to_swap;
423  swapped = true;
424  }
425  }
426  j--;
427  } while(swapped);
428  }
429 }
uint8_t input_buffer[AP_BEACON_MARVELMIND_BUF_SIZE]
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
#define AP_BEACON_MARVELMIND_DISTANCES_DATAGRAM_ID
uint16_t calc_crc_modbus(uint8_t *buf, uint16_t len)
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
enum AP_Beacon_Marvelmind::@13 parse_state
Vector3< float > Vector3f
Definition: vector3.h:246
StationaryBeaconPosition beacons[AP_BEACON_MAX_BEACONS]
AP_Beacon_Marvelmind(AP_Beacon &frontend, AP_SerialManager &serial_manager)
void set_beacon_distance(uint8_t beacon_instance, float distance)
virtual void begin(uint32_t baud)=0
Interface definition for the various Ground Control System.
#define Debug(level, fmt, args ...)
#define AP_BEACON_MARVELMIND_POSITIONS_DATAGRAM_HIGHRES_ID
#define AP_BEACON_MAX_BEACONS
Definition: AP_Beacon.h:25
float distance
Definition: location.cpp:94
StationaryBeaconPosition * get_or_alloc_beacon(uint8_t address)
uint32_t find_baudrate(enum SerialProtocol protocol, uint8_t instance) const
#define x(i)
#define f(i)
Vector3f beacon_position_NED__m[AP_BEACON_MAX_BEACONS]
#define AP_BEACON_MARVELMIND_POSITION_DATAGRAM_HIGHRES_ID
uint32_t millis()
Definition: system.cpp:157
#define AP_BEACON_TIMEOUT_MS
Definition: AP_Beacon.h:26
#define AP_BEACON_MARVELMIND_POSITIONS_DATAGRAM_ID
void set_beacon_position(uint8_t beacon_instance, const Vector3f &pos)
virtual int16_t read()=0
virtual uint32_t available()=0
AP_HAL::UARTDriver * uart
#define AP_BEACON_MARVELMIND_POSITION_DATAGRAM_ID
void set_vehicle_position(const Vector3f &pos, float accuracy_estimate)
StationaryBeaconsPositions positions_beacons
int8_t find_beacon_instance(uint8_t address) const
AP_HAL::UARTDriver * find_serial(enum SerialProtocol protocol, uint8_t instance) const