CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Beacon/AP_Beacon_Pozyx.cpp
Views: 1798
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_Beacon_Pozyx.h"
17
18
#if AP_BEACON_POZYX_ENABLED
19
20
#include <AP_HAL/AP_HAL.h>
21
#include <ctype.h>
22
#include <stdio.h>
23
24
extern const AP_HAL::HAL& hal;
25
26
// return true if sensor is basically healthy (we are receiving data)
27
bool AP_Beacon_Pozyx::healthy()
28
{
29
// healthy if we have parsed a message within the past 300ms
30
return ((AP_HAL::millis() - last_update_ms) < AP_BEACON_TIMEOUT_MS);
31
}
32
33
// update the state of the sensor
34
void AP_Beacon_Pozyx::update(void)
35
{
36
if (uart == nullptr) {
37
return;
38
}
39
40
// read any available characters
41
int16_t nbytes = uart->available();
42
while (nbytes-- > 0) {
43
char c = uart->read();
44
45
switch (parse_state) {
46
47
default:
48
case ParseState_WaitingForHeader:
49
if (c == AP_BEACON_POZYX_HEADER) {
50
parse_state = ParseState_WaitingForMsgId;
51
linebuf_len = 0;
52
}
53
break;
54
55
case ParseState_WaitingForMsgId:
56
parse_msg_id = c;
57
switch (parse_msg_id) {
58
case AP_BEACON_POZYX_MSGID_BEACON_CONFIG:
59
case AP_BEACON_POZYX_MSGID_BEACON_DIST:
60
case AP_BEACON_POZYX_MSGID_POSITION:
61
parse_state = ParseState_WaitingForLen;
62
break;
63
default:
64
// invalid message id
65
parse_state = ParseState_WaitingForHeader;
66
break;
67
}
68
break;
69
70
case ParseState_WaitingForLen:
71
parse_msg_len = c;
72
if (parse_msg_len > AP_BEACON_POZYX_MSG_LEN_MAX) {
73
// invalid message length
74
parse_state = ParseState_WaitingForHeader;
75
} else {
76
parse_state = ParseState_WaitingForContents;
77
}
78
break;
79
80
case ParseState_WaitingForContents:
81
// add to buffer
82
linebuf[linebuf_len++] = c;
83
if ((linebuf_len == parse_msg_len) || (linebuf_len == sizeof(linebuf))) {
84
// process buffer
85
parse_buffer();
86
// reset state for next message
87
parse_state = ParseState_WaitingForHeader;
88
}
89
break;
90
}
91
}
92
}
93
94
// parse buffer
95
void AP_Beacon_Pozyx::parse_buffer()
96
{
97
// check crc
98
uint8_t checksum = 0;
99
checksum ^= parse_msg_id;
100
checksum ^= parse_msg_len;
101
for (uint8_t i=0; i<linebuf_len; i++) {
102
checksum ^= linebuf[i];
103
}
104
// return if failed checksum check
105
if (checksum != 0) {
106
return;
107
}
108
109
bool parsed = false;
110
switch (parse_msg_id) {
111
112
case AP_BEACON_POZYX_MSGID_BEACON_CONFIG:
113
{
114
uint8_t beacon_id = linebuf[0];
115
//uint8_t beacon_count = linebuf[1];
116
int32_t beacon_x = (uint32_t)linebuf[5] << 24 | (uint32_t)linebuf[4] << 16 | (uint32_t)linebuf[3] << 8 | (uint32_t)linebuf[2];
117
int32_t beacon_y = (uint32_t)linebuf[9] << 24 | (uint32_t)linebuf[8] << 16 | (uint32_t)linebuf[7] << 8 | (uint32_t)linebuf[6];
118
int32_t beacon_z = (uint32_t)linebuf[13] << 24 | (uint32_t)linebuf[12] << 16 | (uint32_t)linebuf[11] << 8 | (uint32_t)linebuf[10];
119
Vector3f beacon_pos(beacon_x * 0.001f, beacon_y * 0.001f, -beacon_z * 0.001f);
120
if (beacon_pos.length() <= AP_BEACON_DISTANCE_MAX) {
121
set_beacon_position(beacon_id, beacon_pos);
122
parsed = true;
123
}
124
}
125
break;
126
127
case AP_BEACON_POZYX_MSGID_BEACON_DIST:
128
{
129
uint8_t beacon_id = linebuf[0];
130
uint32_t beacon_distance = (uint32_t)linebuf[4] << 24 | (uint32_t)linebuf[3] << 16 | (uint32_t)linebuf[2] << 8 | (uint32_t)linebuf[1];
131
float beacon_dist = beacon_distance/1000.0f;
132
if (beacon_dist <= AP_BEACON_DISTANCE_MAX) {
133
set_beacon_distance(beacon_id, beacon_dist);
134
parsed = true;
135
}
136
}
137
break;
138
139
case AP_BEACON_POZYX_MSGID_POSITION:
140
{
141
int32_t vehicle_x = (uint32_t)linebuf[3] << 24 | (uint32_t)linebuf[2] << 16 | (uint32_t)linebuf[1] << 8 | (uint32_t)linebuf[0];
142
int32_t vehicle_y = (uint32_t)linebuf[7] << 24 | (uint32_t)linebuf[6] << 16 | (uint32_t)linebuf[5] << 8 | (uint32_t)linebuf[4];
143
int32_t vehicle_z = (uint32_t)linebuf[11] << 24 | (uint32_t)linebuf[10] << 16 | (uint32_t)linebuf[9] << 8 | (uint32_t)linebuf[8];
144
int16_t position_error = (uint32_t)linebuf[13] << 8 | (uint32_t)linebuf[12];
145
Vector3f veh_pos(Vector3f(vehicle_x * 0.001f, vehicle_y * 0.001f, -vehicle_z * 0.001f));
146
if (veh_pos.length() <= AP_BEACON_DISTANCE_MAX) {
147
set_vehicle_position(veh_pos, position_error);
148
parsed = true;
149
}
150
}
151
break;
152
153
default:
154
// unrecognised message id
155
break;
156
}
157
158
// record success
159
if (parsed) {
160
last_update_ms = AP_HAL::millis();
161
}
162
}
163
164
#endif // AP_BEACON_POZYX_ENABLED
165
166