APM:Libraries
AP_GPS_SBP.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 //
17 // Swift Navigation SBP GPS driver for ArduPilot.
18 // Code by Niels Joubert
19 //
20 // Swift Binary Protocol format: http://docs.swift-nav.com/
21 //
22 
23 #include "AP_GPS.h"
24 #include "AP_GPS_SBP.h"
25 #include <DataFlash/DataFlash.h>
26 
27 extern const AP_HAL::HAL& hal;
28 
29 #define SBP_DEBUGGING 1
30 #define SBP_HW_LOGGING 1
31 
32 #define SBP_TIMEOUT_HEATBEAT 4000
33 #define SBP_TIMEOUT_PVT 500
34 
35 #if SBP_DEBUGGING
36  # define Debug(fmt, args ...) \
37 do { \
38  hal.console->printf("%s:%d: " fmt "\n", \
39  __FUNCTION__, __LINE__, \
40  ## args); \
41  hal.scheduler->delay(1); \
42 } while(0)
43 #else
44  # define Debug(fmt, args ...)
45 #endif
46 
48  AP_HAL::UARTDriver *_port) :
49  AP_GPS_Backend(_gps, _state, _port)
50 {
51 
52  Debug("SBP Driver Initialized");
53 
55 
56  //Externally visible state
59 
60 }
61 
62 // Process all bytes available from the stream
63 //
64 bool
66 {
67 
68  //Invariant: Calling this function processes *all* data current in the UART buffer.
69  //
70  //IMPORTANT NOTICE: This function is NOT CALLED for several seconds
71  // during arming. That should not cause the driver to die. Process *all* waiting messages
72 
73  _sbp_process();
74 
75  return _attempt_state_update();
76 
77 }
78 
79 void
80 AP_GPS_SBP::inject_data(const uint8_t *data, uint16_t len)
81 {
82 
83  if (port->txspace() > len) {
85  port->write(data, len);
86  } else {
87  Debug("PIKSI: Not enough TXSPACE");
88  }
89 
90 }
91 
92 //This attempts to reads all SBP messages from the incoming port.
93 //Returns true if a new message was read, false if we failed to read a message.
94 void
96 {
97 
98  while (port->available() > 0) {
99  uint8_t temp = port->read();
100  uint16_t crc;
101 
102 
103  //This switch reads one character at a time,
104  //parsing it into buffers until a full message is dispatched
105  switch (parser_state.state) {
107  if (temp == SBP_PREAMBLE) {
108  parser_state.n_read = 0;
110  }
111  break;
112 
114  *((uint8_t*)&(parser_state.msg_type) + parser_state.n_read) = temp;
115  parser_state.n_read += 1;
116  if (parser_state.n_read >= 2) {
117  parser_state.n_read = 0;
119  }
120  break;
121 
123  *((uint8_t*)&(parser_state.sender_id) + parser_state.n_read) = temp;
124  parser_state.n_read += 1;
125  if (parser_state.n_read >= 2) {
126  parser_state.n_read = 0;
128  }
129  break;
130 
132  parser_state.msg_len = temp;
133  parser_state.n_read = 0;
135  break;
136 
138  *((uint8_t*)&(parser_state.msg_buff) + parser_state.n_read) = temp;
139  parser_state.n_read += 1;
141  parser_state.n_read = 0;
143  }
144  break;
145 
147  *((uint8_t*)&(parser_state.crc) + parser_state.n_read) = temp;
148  parser_state.n_read += 1;
149  if (parser_state.n_read >= 2) {
151 
152  crc = crc16_ccitt((uint8_t*)&(parser_state.msg_type), 2, 0);
153  crc = crc16_ccitt((uint8_t*)&(parser_state.sender_id), 2, crc);
154  crc = crc16_ccitt(&(parser_state.msg_len), 1, crc);
156  if (parser_state.crc == crc) {
158  } else {
159  Debug("CRC Error Occurred!");
160  crc_error_counter += 1;
161  }
162 
164  }
165  break;
166 
167  default:
169  break;
170  }
171  }
172 }
173 
174 
175 //INVARIANT: A fully received message with correct CRC is currently in parser_state
176 void
178  switch (parser_state.msg_type) {
181  break;
182 
185  break;
186 
187  case SBP_VEL_NED_MSGTYPE:
188  memcpy(&last_vel_ned, parser_state.msg_buff, sizeof(last_vel_ned));
189  break;
190 
191  case SBP_POS_LLH_MSGTYPE: {
192  struct sbp_pos_llh_t *pos_llh = (struct sbp_pos_llh_t*)parser_state.msg_buff;
193  // Check if this is a single point or RTK solution
194  // flags = 0 -> single point
195  if (pos_llh->flags == 0) {
196  last_pos_llh_spp = *pos_llh;
197  } else if (pos_llh->flags == 1 || pos_llh->flags == 2) {
198  last_pos_llh_rtk = *pos_llh;
199  }
200  break;
201  }
202 
203  case SBP_DOPS_MSGTYPE:
204  memcpy(&last_dops, parser_state.msg_buff, sizeof(last_dops));
205  break;
206 
208  //INTENTIONALLY BLANK
209  //Currently unhandled, but logged after switch statement.
210  break;
211 
212  case SBP_IAR_STATE_MSGTYPE: {
215  break;
216  }
217 
218  default:
219  // log anyway if it's an unsupported message.
220  // The log mask will be used to adjust or suppress logging
221  break;
222  }
223 
225 }
226 
227 bool
229 {
230 
231  // If we currently have heartbeats
232  // - NO FIX
233  //
234  // If we have a full update available, save it
235  //
236  uint32_t now = AP_HAL::millis();
237  bool ret = false;
238 
240 
242  Debug("No Heartbeats from Piksi! Driver Ready to Die!");
243 
244  } else if (last_pos_llh_rtk.tow == last_vel_ned.tow
245  && abs((int32_t) (last_gps_time.tow - last_vel_ned.tow)) < 10000
246  && abs((int32_t) (last_dops.tow - last_vel_ned.tow)) < 60000
248 
249  // Use the RTK position
250  sbp_pos_llh_t *pos_llh = &last_pos_llh_rtk;
251 
252  // Update time state
255 
257 
258  // Update velocity state
259  state.velocity[0] = (float)(last_vel_ned.n * 1.0e-3);
260  state.velocity[1] = (float)(last_vel_ned.e * 1.0e-3);
261  state.velocity[2] = (float)(last_vel_ned.d * 1.0e-3);
263 
264  float ground_vector_sq = state.velocity[0]*state.velocity[0] + state.velocity[1]*state.velocity[1];
265  state.ground_speed = safe_sqrt(ground_vector_sq);
266 
268 
269  // Update position state
270 
271  state.location.lat = (int32_t) (pos_llh->lat * (double)1e7);
272  state.location.lng = (int32_t) (pos_llh->lon * (double)1e7);
273  state.location.alt = (int32_t) (pos_llh->height * 100);
274  state.num_sats = pos_llh->n_sats;
275 
276  if (pos_llh->flags == 0) {
278  } else if (pos_llh->flags == 2) {
280  } else if (pos_llh->flags == 1) {
282  }
283 
287 
289  ret = true;
290 
291  } else if (now - last_full_update_cpu_ms > SBP_TIMEOUT_PVT) {
292 
293  //INVARIANT: If we currently have a fix, ONLY return true after a full update.
294 
296  ret = true;
297 
298  } else {
299 
300  //No timeouts yet, no data yet, nothing has happened.
301 
302  }
303 
304  return ret;
305 
306 }
307 
308 
309 
310 bool
312 {
313  // This switch reads one character at a time, if we find something that
314  // looks like our preamble we'll try to read the full message length,
315  // calculating the CRC. If the CRC matches, we have an SBP GPS!
316 
317  switch (state.state) {
319  if (data == SBP_PREAMBLE) {
320  state.n_read = 0;
321  state.crc_so_far = 0;
323  }
324  break;
325 
327  *((uint8_t*)&(state.msg_type) + state.n_read) = data;
328  state.crc_so_far = crc16_ccitt(&data, 1, state.crc_so_far);
329  state.n_read += 1;
330  if (state.n_read >= 2) {
331  state.n_read = 0;
333  }
334  break;
335 
337  state.crc_so_far = crc16_ccitt(&data, 1, state.crc_so_far);
338  state.n_read += 1;
339  if (state.n_read >= 2) {
340  state.n_read = 0;
342  }
343  break;
344 
346  state.crc_so_far = crc16_ccitt(&data, 1, state.crc_so_far);
347  state.msg_len = data;
348  state.n_read = 0;
350  break;
351 
353  if (state.msg_type == SBP_HEARTBEAT_MSGTYPE && state.n_read < 4) {
354  *((uint8_t*)&(state.heartbeat_buff) + state.n_read) = data;
355  }
356  state.crc_so_far = crc16_ccitt(&data, 1, state.crc_so_far);
357  state.n_read += 1;
358  if (state.n_read >= state.msg_len) {
359  state.n_read = 0;
361  }
362  break;
363 
365  *((uint8_t*)&(state.crc) + state.n_read) = data;
366  state.n_read += 1;
367  if (state.n_read >= 2) {
369  if (state.crc == state.crc_so_far
370  && state.msg_type == SBP_HEARTBEAT_MSGTYPE) {
371  struct sbp_heartbeat_t* heartbeat = ((struct sbp_heartbeat_t*)state.heartbeat_buff);
372  return heartbeat->protocol_major == 0;
373  }
374  return false;
375  }
376  break;
377 
378  default:
380  break;
381  }
382  return false;
383 }
384 
385 #if SBP_HW_LOGGING
386 
387 void
389 {
390 
391  if (!should_df_log()) {
392  return;
393  }
394 
395  struct log_SbpHealth pkt = {
401  };
402 
403  DataFlash_Class::instance()->WriteBlock(&pkt, sizeof(pkt));
404 };
405 
406 void
408  uint16_t sender_id,
409  uint8_t msg_len,
410  uint8_t *msg_buff) {
411  if (!should_df_log()) {
412  return;
413  }
414 
415  //MASK OUT MESSAGES WE DON'T WANT TO LOG
416  if (( ((uint16_t) gps._sbp_logmask) & msg_type) == 0) {
417  return;
418  }
419 
420  uint64_t time_us = AP_HAL::micros64();
421  uint8_t pages = 1;
422 
423  if (msg_len > 48) {
424  pages += (msg_len - 48) / 104 + 1;
425  }
426 
427  struct log_SbpRAWH pkt = {
429  time_us : time_us,
430  msg_type : msg_type,
432  index : 1,
433  pages : pages,
434  msg_len : msg_len,
435  };
436  memcpy(pkt.data, msg_buff, MIN(msg_len, 48));
437  DataFlash_Class::instance()->WriteBlock(&pkt, sizeof(pkt));
438 
439  for (uint8_t i = 0; i < pages - 1; i++) {
440  struct log_SbpRAWM pkt2 = {
442  time_us : time_us,
443  msg_type : msg_type,
445  index : uint8_t(i + 2),
446  pages : pages,
447  msg_len : msg_len,
448  };
449  memcpy(pkt2.data, &msg_buff[48 + i * 104], MIN(msg_len - (48 + i * 104), 104));
450  DataFlash_Class::instance()->WriteBlock(&pkt2, sizeof(pkt2));
451  }
452 };
453 
454 #endif // SBP_HW_LOGGING
Definition: AP_GPS.h:48
uint32_t time_week_ms
GPS time (milliseconds from start of GPS week)
Definition: AP_GPS.h:133
static const uint16_t SBP_VEL_NED_MSGTYPE
Definition: AP_GPS_SBP.h:80
uint16_t msg_type
Definition: LogStructure.h:945
AP_GPS_SBP(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port)
Definition: AP_GPS_SBP.cpp:47
uint8_t pages
Definition: LogStructure.h:948
uint16_t sender_id
Definition: LogStructure.h:946
uint32_t last_gps_time_ms
the system time we got the last GPS timestamp, milliseconds
Definition: AP_GPS.h:149
float safe_sqrt(const T v)
Definition: AP_Math.cpp:64
#define Debug(fmt, args ...)
Definition: AP_GPS_SBP.cpp:36
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
uint8_t heartbeat_buff[4]
GPS_Status status
driver fix status
Definition: AP_GPS.h:132
uint8_t pages
Definition: LogStructure.h:960
bool have_vertical_velocity
does GPS give vertical velocity? Set to true only once available.
Definition: AP_GPS.h:145
Vector3f velocity
3D velocity in m/s, in NED format
Definition: AP_GPS.h:141
uint8_t index
Definition: LogStructure.h:947
struct AP_GPS_SBP::sbp_parser_state_t parser_state
void WriteBlock(const void *pBuffer, uint16_t size)
Definition: DataFlash.cpp:481
virtual uint32_t txspace()=0
uint32_t last_full_update_cpu_ms
Definition: AP_GPS_SBP.h:171
struct sbp_pos_llh_t last_pos_llh_rtk
Definition: AP_GPS_SBP.h:166
static const uint8_t SBP_PREAMBLE
Definition: AP_GPS_SBP.h:68
enum SBP_detect_state::@36 state
void logging_log_full_update()
Definition: AP_GPS_SBP.cpp:388
bool _attempt_state_update()
Definition: AP_GPS_SBP.cpp:228
static const uint16_t SBP_IAR_STATE_MSGTYPE
Definition: AP_GPS_SBP.h:82
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
void _sbp_process_message()
Definition: AP_GPS_SBP.cpp:177
uint8_t msg_len
Definition: LogStructure.h:949
#define MIN(a, b)
Definition: usb_conf.h:215
Receiving valid messages and 3D RTK Fixed.
Definition: AP_GPS.h:103
AP_GPS & gps
access to frontend (for parameters)
Definition: GPS_Backend.h:70
struct sbp_vel_ned_t last_vel_ned
Definition: AP_GPS_SBP.h:167
uint16_t sender_id
Definition: LogStructure.h:958
float wrap_360(const T angle, float unit_mod)
Definition: AP_Math.cpp:123
struct sbp_pos_llh_t last_pos_llh_spp
Definition: AP_GPS_SBP.h:165
static const uint16_t SBP_HEARTBEAT_MSGTYPE
Definition: AP_GPS_SBP.h:72
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
static const uint16_t SBP_TRACKING_STATE_MSGTYPE
Definition: AP_GPS_SBP.h:81
uint64_t time_us
Definition: LogStructure.h:936
Receiving valid messages and 3D RTK Float.
Definition: AP_GPS.h:102
static const uint16_t SBP_GPS_TIME_MSGTYPE
Definition: AP_GPS_SBP.h:73
virtual size_t write(uint8_t)=0
uint32_t millis()
Definition: system.cpp:157
uint32_t crc_error_counter
Definition: AP_GPS_SBP.h:177
int32_t rtk_iar_num_hypotheses
Current number of integer ambiguity hypotheses.
Definition: AP_GPS.h:161
static DataFlash_Class * instance(void)
Definition: DataFlash.h:62
uint64_t micros64()
Definition: system.cpp:162
static const uint16_t SBP_POS_LLH_MSGTYPE
Definition: AP_GPS_SBP.h:76
uint64_t time_us
Definition: LogStructure.h:956
uint16_t time_week
GPS week number.
Definition: AP_GPS.h:134
AP_GPS::GPS_State & state
public state for this instance
Definition: GPS_Backend.h:71
uint8_t index
Definition: LogStructure.h:959
virtual int16_t read()=0
uint32_t last_iar_num_hypotheses
Definition: AP_GPS_SBP.h:168
bool should_df_log() const
uint8_t data[48]
Definition: LogStructure.h:951
virtual uint32_t available()=0
Location location
last fix location
Definition: AP_GPS.h:135
uint16_t msg_type
Definition: LogStructure.h:957
#define SBP_TIMEOUT_HEATBEAT
Definition: AP_GPS_SBP.cpp:32
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
void logging_log_raw_sbp(uint16_t msg_type, uint16_t sender_id, uint8_t msg_len, uint8_t *msg_buff)
Definition: AP_GPS_SBP.cpp:407
Receiving valid GPS messages but no lock.
Definition: AP_GPS.h:98
void inject_data(const uint8_t *data, uint16_t len) override
Definition: AP_GPS_SBP.cpp:80
enum AP_GPS_SBP::sbp_parser_state_t::@33 state
void _sbp_process()
Definition: AP_GPS_SBP.cpp:95
uint8_t data[104]
Definition: LogStructure.h:963
static bool _detect(struct SBP_detect_state &state, uint8_t data)
Definition: AP_GPS_SBP.cpp:311
struct sbp_dops_t last_dops
Definition: AP_GPS_SBP.h:164
#define SBP_TIMEOUT_PVT
Definition: AP_GPS_SBP.cpp:33
AP_HAL::UARTDriver * port
UART we are attached to.
Definition: GPS_Backend.h:69
struct sbp_gps_time_t last_gps_time
Definition: AP_GPS_SBP.h:163
float ground_speed
ground speed in m/sec
Definition: AP_GPS.h:136
Receiving valid messages and 3D lock.
Definition: AP_GPS.h:100
#define degrees(x)
Definition: moduletest.c:23
static const uint16_t SBP_DOPS_MSGTYPE
Definition: AP_GPS_SBP.h:74
uint64_t time_us
Definition: LogStructure.h:944
uint8_t msg_len
Definition: LogStructure.h:961
bool read()
Definition: AP_GPS_SBP.cpp:65
uint16_t hdop
horizontal dilution of precision in cm
Definition: AP_GPS.h:138
#define LOG_PACKET_HEADER_INIT(id)
Definition: LogStructure.h:8
uint16_t crc16_ccitt(const uint8_t *buf, uint32_t len, uint16_t crc)
Definition: edc.cpp:52
AP_Int16 _sbp_logmask
Definition: AP_GPS.h:426
uint32_t last_injected_data_ms
Definition: AP_GPS_SBP.h:161
uint8_t num_sats
Number of visible satellites.
Definition: AP_GPS.h:140
uint32_t last_heatbeat_received_ms
Definition: AP_GPS_SBP.h:160
uint32_t last_full_update_tow
Definition: AP_GPS_SBP.h:170
float ground_course
ground course in degrees
Definition: AP_GPS.h:137