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_GPS/AP_GPS_SIRF.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
//
17
// SiRF Binary GPS driver for ArduPilot and ArduPilotMega.
18
// Code by Michael Smith.
19
//
20
21
#include "AP_GPS_config.h"
22
23
#if AP_GPS_SIRF_ENABLED
24
25
#include "AP_GPS_SIRF.h"
26
#include <AP_HAL/utility/sparse-endian.h>
27
#include <stdint.h>
28
29
// Initialisation messages
30
//
31
// Turn off all messages except for 0x29.
32
//
33
// XXX the bytes show up on the wire, but at least my test unit (EM-411) seems to ignore them.
34
//
35
const uint8_t AP_GPS_SIRF::_initialisation_blob[] = {
36
0xa0, 0xa2, 0x00, 0x08, 0xa6, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xa8, 0xb0, 0xb3,
37
0xa0, 0xa2, 0x00, 0x08, 0xa6, 0x00, 0x29, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0xd0, 0xb0, 0xb3
38
};
39
40
AP_GPS_SIRF::AP_GPS_SIRF(AP_GPS &_gps, AP_GPS::Params &_params, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) :
41
AP_GPS_Backend(_gps, _params, _state, _port)
42
{
43
gps.send_blob_start(state.instance, (const char *)_initialisation_blob, sizeof(_initialisation_blob));
44
}
45
46
47
// Process bytes available from the stream
48
//
49
// The stream is assumed to contain only messages we recognise. If it
50
// contains other messages, and those messages contain the preamble
51
// bytes, it is possible for this code to fail to synchronise to the
52
// stream immediately. Without buffering the entire message and
53
// re-processing it from the top, this is unavoidable. The parser
54
// attempts to avoid this when possible.
55
//
56
bool
57
AP_GPS_SIRF::read(void)
58
{
59
uint8_t data;
60
int16_t numc;
61
bool parsed = false;
62
63
numc = port->available();
64
while(numc--) {
65
66
// read the next byte
67
data = port->read();
68
69
switch(_step) {
70
71
// Message preamble detection
72
//
73
// If we fail to match any of the expected bytes, we reset
74
// the state machine and re-consider the failed byte as
75
// the first byte of the preamble. This improves our
76
// chances of recovering from a mismatch and makes it less
77
// likely that we will be fooled by the preamble appearing
78
// as data in some other message.
79
//
80
case 1:
81
if (PREAMBLE2 == data) {
82
_step++;
83
break;
84
}
85
_step = 0;
86
FALLTHROUGH;
87
case 0:
88
if(PREAMBLE1 == data)
89
_step++;
90
break;
91
92
// Message length
93
//
94
// We always collect the length so that we can avoid being
95
// fooled by preamble bytes in messages.
96
//
97
case 2:
98
_step++;
99
_payload_length = (uint16_t)data << 8;
100
break;
101
case 3:
102
_step++;
103
_payload_length |= data;
104
_payload_counter = 0;
105
_checksum = 0;
106
break;
107
108
// Message header processing
109
//
110
// We sniff the message ID to determine whether we are going
111
// to gather the message bytes or just discard them.
112
//
113
case 4:
114
_step++;
115
_accumulate(data);
116
_payload_length--;
117
_gather = false;
118
switch(data) {
119
case MSG_GEONAV:
120
if (_payload_length == sizeof(sirf_geonav)) {
121
_gather = true;
122
_msg_id = data;
123
}
124
break;
125
}
126
break;
127
128
// Receive message data
129
//
130
// Note that we are effectively guaranteed by the protocol
131
// that the checksum and postamble cannot be mistaken for
132
// the preamble, so if we are discarding bytes in this
133
// message when the payload is done we return directly
134
// to the preamble detector rather than bothering with
135
// the checksum logic.
136
//
137
case 5:
138
if (_gather) { // gather data if requested
139
_accumulate(data);
140
_buffer[_payload_counter] = data;
141
if (++_payload_counter == _payload_length)
142
_step++;
143
} else {
144
if (++_payload_counter == _payload_length)
145
_step = 0;
146
}
147
break;
148
149
// Checksum and message processing
150
//
151
case 6:
152
_step++;
153
if ((_checksum >> 8) != data) {
154
_step = 0;
155
}
156
break;
157
case 7:
158
_step = 0;
159
if ((_checksum & 0xff) != data) {
160
break;
161
}
162
if (_gather) {
163
parsed = _parse_gps(); // Parse the new GPS packet
164
}
165
}
166
}
167
return(parsed);
168
}
169
170
bool
171
AP_GPS_SIRF::_parse_gps(void)
172
{
173
switch(_msg_id) {
174
case MSG_GEONAV:
175
//time = _swapl(&_buffer.nav.time);
176
// parse fix type
177
if (_buffer.nav.fix_invalid) {
178
state.status = AP_GPS::NO_FIX;
179
}else if ((_buffer.nav.fix_type & FIX_MASK) == FIX_3D) {
180
state.status = AP_GPS::GPS_OK_FIX_3D;
181
}else{
182
state.status = AP_GPS::GPS_OK_FIX_2D;
183
}
184
state.location.lat = int32_t(be32toh(_buffer.nav.latitude));
185
state.location.lng = int32_t(be32toh(_buffer.nav.longitude));
186
const int32_t alt_amsl = int32_t(be32toh(_buffer.nav.altitude_msl));
187
const int32_t alt_ellipsoid = int32_t(be32toh(_buffer.nav.altitude_ellipsoid));
188
state.undulation = (alt_amsl - alt_ellipsoid)*0.01;
189
state.have_undulation = true;
190
set_alt_amsl_cm(state, alt_amsl);
191
state.ground_speed = int32_t(be32toh(_buffer.nav.ground_speed))*0.01f;
192
state.ground_course = wrap_360(int16_t(be16toh(_buffer.nav.ground_course)*0.01f));
193
state.num_sats = _buffer.nav.satellites;
194
fill_3d_velocity();
195
return true;
196
}
197
return false;
198
}
199
200
void
201
AP_GPS_SIRF::_accumulate(uint8_t val)
202
{
203
_checksum = (_checksum + val) & 0x7fff;
204
}
205
206
207
208
/*
209
detect a SIRF GPS
210
*/
211
bool AP_GPS_SIRF::_detect(struct SIRF_detect_state &state, uint8_t data)
212
{
213
switch (state.step) {
214
case 1:
215
if (PREAMBLE2 == data) {
216
state.step++;
217
break;
218
}
219
state.step = 0;
220
FALLTHROUGH;
221
case 0:
222
state.payload_length = state.payload_counter = state.checksum = 0;
223
if (PREAMBLE1 == data)
224
state.step++;
225
break;
226
case 2:
227
state.step++;
228
if (data != 0) {
229
// only look for short messages
230
state.step = 0;
231
}
232
break;
233
case 3:
234
state.step++;
235
state.payload_length = data;
236
break;
237
case 4:
238
state.checksum = (state.checksum + data) & 0x7fff;
239
if (++state.payload_counter == state.payload_length) {
240
state.step++;
241
}
242
break;
243
case 5:
244
state.step++;
245
if ((state.checksum >> 8) != data) {
246
state.step = 0;
247
}
248
break;
249
case 6:
250
state.step = 0;
251
if ((state.checksum & 0xff) == data) {
252
return true;
253
}
254
}
255
return false;
256
}
257
258
#endif // AP_GPS_SIRF_ENABLED
259
260