APM:Libraries
AP_Beacon_Pozyx.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 #include <AP_HAL/AP_HAL.h>
17 #include "AP_Beacon_Pozyx.h"
18 #include <ctype.h>
19 #include <stdio.h>
20 
21 extern const AP_HAL::HAL& hal;
22 
23 // constructor
25  AP_Beacon_Backend(frontend),
26  linebuf_len(0)
27 {
29  if (uart != nullptr) {
31  }
32 }
33 
34 // return true if sensor is basically healthy (we are receiving data)
36 {
37  // healthy if we have parsed a message within the past 300ms
39 }
40 
41 // update the state of the sensor
43 {
44  static uint8_t counter = 0;
45  counter++;
46  if (counter > 200) {
47  counter = 0;
48  }
49 
50  if (uart == nullptr) {
51  return;
52  }
53 
54  // read any available characters
55  int16_t nbytes = uart->available();
56  while (nbytes-- > 0) {
57  char c = uart->read();
58 
59  switch (parse_state) {
60 
61  default:
63  if (c == AP_BEACON_POZYX_HEADER) {
65  linebuf_len = 0;
66  }
67  break;
68 
70  parse_msg_id = c;
71  switch (parse_msg_id) {
76  break;
77  default:
78  // invalid message id
80  break;
81  }
82  break;
83 
85  parse_msg_len = c;
87  // invalid message length
89  } else {
91  }
92  break;
93 
95  // add to buffer
96  linebuf[linebuf_len++] = c;
97  if ((linebuf_len == parse_msg_len) || (linebuf_len == sizeof(linebuf))) {
98  // process buffer
99  parse_buffer();
100  // reset state for next message
102  }
103  break;
104  }
105  }
106 }
107 
108 // parse buffer
110 {
111  // check crc
112  uint8_t checksum = 0;
113  checksum ^= parse_msg_id;
114  checksum ^= parse_msg_len;
115  for (uint8_t i=0; i<linebuf_len; i++) {
116  checksum ^= linebuf[i];
117  }
118  // return if failed checksum check
119  if (checksum != 0) {
120  return;
121  }
122 
123  bool parsed = false;
124  switch (parse_msg_id) {
125 
127  {
128  uint8_t beacon_id = linebuf[0];
129  //uint8_t beacon_count = linebuf[1];
130  int32_t beacon_x = (uint32_t)linebuf[5] << 24 | (uint32_t)linebuf[4] << 16 | (uint32_t)linebuf[3] << 8 | (uint32_t)linebuf[2];
131  int32_t beacon_y = (uint32_t)linebuf[9] << 24 | (uint32_t)linebuf[8] << 16 | (uint32_t)linebuf[7] << 8 | (uint32_t)linebuf[6];
132  int32_t beacon_z = (uint32_t)linebuf[13] << 24 | (uint32_t)linebuf[12] << 16 | (uint32_t)linebuf[11] << 8 | (uint32_t)linebuf[10];
133  Vector3f beacon_pos(beacon_x / 1000.0f, beacon_y / 1000.0f, -beacon_z / 1000.0f);
134  if (beacon_pos.length() <= AP_BEACON_DISTANCE_MAX) {
135  set_beacon_position(beacon_id, beacon_pos);
136  parsed = true;
137  }
138  }
139  break;
140 
142  {
143  uint8_t beacon_id = linebuf[0];
144  uint32_t beacon_distance = (uint32_t)linebuf[4] << 24 | (uint32_t)linebuf[3] << 16 | (uint32_t)linebuf[2] << 8 | (uint32_t)linebuf[1];
145  float beacon_dist = beacon_distance/1000.0f;
146  if (beacon_dist <= AP_BEACON_DISTANCE_MAX) {
147  set_beacon_distance(beacon_id, beacon_dist);
148  parsed = true;
149  }
150  }
151  break;
152 
154  {
155  int32_t vehicle_x = (uint32_t)linebuf[3] << 24 | (uint32_t)linebuf[2] << 16 | (uint32_t)linebuf[1] << 8 | (uint32_t)linebuf[0];
156  int32_t vehicle_y = (uint32_t)linebuf[7] << 24 | (uint32_t)linebuf[6] << 16 | (uint32_t)linebuf[5] << 8 | (uint32_t)linebuf[4];
157  int32_t vehicle_z = (uint32_t)linebuf[11] << 24 | (uint32_t)linebuf[10] << 16 | (uint32_t)linebuf[9] << 8 | (uint32_t)linebuf[8];
158  int16_t position_error = (uint32_t)linebuf[13] << 8 | (uint32_t)linebuf[12];
159  Vector3f veh_pos(Vector3f(vehicle_x / 1000.0f, vehicle_y / 1000.0f, -vehicle_z / 1000.0f));
160  if (veh_pos.length() <= AP_BEACON_DISTANCE_MAX) {
161  set_vehicle_position(veh_pos, position_error);
162  parsed = true;
163  }
164  }
165  break;
166 
167  default:
168  // unrecognised message id
169  break;
170  }
171 
172  // record success
173  if (parsed) {
175  }
176 }
#define AP_BEACON_POZYX_MSGID_BEACON_CONFIG
uint8_t linebuf[AP_BEACON_POZYX_MSG_LEN_MAX]
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
static uint8_t counter
Vector3< float > Vector3f
Definition: vector3.h:246
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
AP_Beacon_Pozyx(AP_Beacon &frontend, AP_SerialManager &serial_manager)
void set_beacon_distance(uint8_t beacon_instance, float distance)
virtual void begin(uint32_t baud)=0
AP_HAL::UARTDriver * uart
#define AP_BEACON_POZYX_HEADER
uint32_t find_baudrate(enum SerialProtocol protocol, uint8_t instance) const
#define AP_BEACON_DISTANCE_MAX
#define AP_BEACON_POZYX_MSGID_BEACON_DIST
#define f(i)
uint32_t millis()
Definition: system.cpp:157
#define AP_BEACON_TIMEOUT_MS
Definition: AP_Beacon.h:26
uint32_t last_update_ms
void set_beacon_position(uint8_t beacon_instance, const Vector3f &pos)
#define AP_BEACON_POZYX_MSG_LEN_MAX
virtual int16_t read()=0
float length(void) const
Definition: vector3.cpp:288
virtual uint32_t available()=0
enum AP_Beacon_Pozyx::ParseState parse_state
void set_vehicle_position(const Vector3f &pos, float accuracy_estimate)
#define AP_BEACON_POZYX_MSGID_POSITION
AP_HAL::UARTDriver * find_serial(enum SerialProtocol protocol, uint8_t instance) const