APM:Libraries
AP_GPS_SBP2.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_SBP2.h"
25 #include <DataFlash/DataFlash.h>
27 #include <GCS_MAVLink/GCS.h>
28 
29 extern const AP_HAL::HAL& hal;
30 
31 #define SBP_DEBUGGING 0
32 #define SBP_INFOREPORTING 1
33 
34 //INVARIANT: We expect SBP to give us a heartbeat in less than 2 seconds.
35 // This is more lax than the default Piksi settings,
36 // and we assume the user hasn't reconfigured their Piksi to longer heartbeat intervals
37 #define SBP_TIMEOUT_HEARTBEAT 2000
38 
39 #if SBP_DEBUGGING
40  # define Debug(fmt, args ...) \
41 do { \
42  hal.console->printf("%s:%d: " fmt "\n", \
43  __FUNCTION__, __LINE__, \
44  ## args); \
45  hal.scheduler->delay(1); \
46 } while(0)
47 #else
48  # define Debug(fmt, args ...)
49 #endif
50 
51 #if SBP_INFOREPORTING
52  # define Info(fmt, args ...) \
53 do { \
54  gcs().send_text(MAV_SEVERITY_INFO, fmt "\n", ## args); \
55 } while(0)
56 #else
57  # define Info(fmt, args ...)
58 #endif
59 
60 
62  AP_HAL::UARTDriver *_port) :
63  AP_GPS_Backend(_gps, _state, _port)
64 {
65  Debug("SBP Driver Initialized");
67 }
68 
69 // Process all bytes available from the stream
70 //
71 bool
73 {
74  //Invariant: Calling this function processes *all* data current in the UART buffer.
75  //
76  //IMPORTANT NOTICE: This function is NOT CALLED for several seconds
77  // during arming. That should not cause the driver to die. Process *all* waiting messages
78 
79  _sbp_process();
80  return _attempt_state_update();
81 }
82 
83 void
84 AP_GPS_SBP2::inject_data(const uint8_t *data, uint16_t len)
85 {
86  if (port->txspace() > len) {
88  port->write(data, len);
89  } else {
90  Debug("PIKSI: Not enough TXSPACE");
91  }
92 }
93 
94 //This attempts to reads all SBP messages from the incoming port.
95 //Returns true if a new message was read, false if we failed to read a message.
96 void
98 {
99  uint32_t nleft = port->available();
100  while (nleft > 0) {
101  nleft--;
102  uint8_t temp = port->read();
103  uint16_t crc;
104 
105  //This switch reads one character at a time,
106  //parsing it into buffers until a full message is dispatched
107  switch (parser_state.state) {
109  if (temp == SBP_PREAMBLE) {
110  parser_state.n_read = 0;
112  }
113  break;
114 
116  *((uint8_t*)&(parser_state.msg_type) + parser_state.n_read) = temp;
117  parser_state.n_read += 1;
118  if (parser_state.n_read >= 2) {
119  parser_state.n_read = 0;
121  }
122  break;
123 
125  *((uint8_t*)&(parser_state.sender_id) + parser_state.n_read) = temp;
126  parser_state.n_read += 1;
127  if (parser_state.n_read >= 2) {
128  parser_state.n_read = 0;
130  }
131  break;
132 
134  parser_state.msg_len = temp;
135  parser_state.n_read = 0;
137  break;
138 
140  *((uint8_t*)&(parser_state.msg_buff) + parser_state.n_read) = temp;
141  parser_state.n_read += 1;
143  parser_state.n_read = 0;
145  }
146  break;
147 
149  *((uint8_t*)&(parser_state.crc) + parser_state.n_read) = temp;
150  parser_state.n_read += 1;
151  if (parser_state.n_read >= 2) {
153 
154  crc = crc16_ccitt((uint8_t*)&(parser_state.msg_type), 2, 0);
155  crc = crc16_ccitt((uint8_t*)&(parser_state.sender_id), 2, crc);
156  crc = crc16_ccitt(&(parser_state.msg_len), 1, crc);
158  if (parser_state.crc == crc) {
160  } else {
161  Debug("CRC Error Occurred!");
162  crc_error_counter += 1;
163  }
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  //Here, we copy messages into local structs.
179  switch (parser_state.msg_type) {
181  memcpy(&last_heartbeat, parser_state.msg_buff, sizeof(struct sbp_heartbeat_t));
183  break;
184 
186  memcpy(&last_gps_time, parser_state.msg_buff, sizeof(struct sbp_gps_time_t));
187  break;
188 
189  case SBP_VEL_NED_MSGTYPE:
190  memcpy(&last_vel_ned, parser_state.msg_buff, sizeof(struct sbp_vel_ned_t));
191  break;
192 
193  case SBP_POS_LLH_MSGTYPE:
194  memcpy(&last_pos_llh, parser_state.msg_buff, sizeof(struct sbp_pos_llh_t));
195  break;
196 
197  case SBP_DOPS_MSGTYPE:
198  memcpy(&last_dops, parser_state.msg_buff, sizeof(struct sbp_dops_t));
199  break;
200 
202  memcpy(&last_event, parser_state.msg_buff, sizeof(struct sbp_ext_event_t));
204  break;
205 
206  default:
207  break;
208  }
209 
210  // send all messages we receive to log, even if it's an unsupported message,
211  // so we can do additional post-processing from Dataflash logs.
212  // The log mask will be used to adjust or suppress logging
214 }
215 
216 int32_t
217 AP_GPS_SBP2::distMod(int32_t tow1_ms, int32_t tow2_ms, int32_t mod) {
218  return MIN(abs(tow1_ms - tow2_ms), mod - abs(tow1_ms - tow2_ms));
219 }
220 
221 bool
223 {
225  return false;
226 
227  uint32_t now = AP_HAL::millis();
228 
230 
232  Info("No Heartbeats from Piksi! Status to NO_FIX.");
233  return false;
234 
235  } else if (last_heartbeat.protocol_major != 2) {
236 
238  Info("Received a heartbeat from non-SBPv2 device. Current driver only supports SBPv2. Status to NO_FIX.");
239  return false;
240 
241  } else if (last_heartbeat.nap_error == 1 ||
242  last_heartbeat.io_error == 1 ||
243  last_heartbeat.sys_error == 1) {
244 
246 
247  Info("Piksi reported an error. Status to NO_FIX.");
248  Debug(" ext_antenna: %d", last_heartbeat.ext_antenna);
249  Debug(" res2: %d", last_heartbeat.res2);
250  Debug(" protocol_major: %d", last_heartbeat.protocol_major);
251  Debug(" protocol_minor: %d", last_heartbeat.protocol_minor);
252  Debug(" res: %d", last_heartbeat.res);
253  Debug(" nap_error: %d", last_heartbeat.nap_error);
254  Debug(" io_error: %d", last_heartbeat.io_error);
255  Debug(" sys_error: %d", last_heartbeat.sys_error);
256 
257  return false;
258 
259  } else if (last_pos_llh.tow == last_vel_ned.tow
263 
264  //We have an aligned VEL and LLH, and a recent DOPS and TIME.
265 
266  //
267  // Check Flags for Valid Messages
268  //
269  if (last_gps_time.flags.fix_mode == 0 ||
270  last_vel_ned.flags.fix_mode == 0 ||
271  last_pos_llh.flags.fix_mode == 0 ||
272  last_dops.flags.fix_mode == 0) {
273 
274  Debug("Message Marked as Invalid. NO FIX! Flags: {GPS_TIME: %d, VEL_NED: %d, POS_LLH: %d, DOPS: %d}",
279 
281  return false;
282  }
283 
284  //
285  // Update external time and accuracy state
286  //
291  state.last_gps_time_ms = now;
292 
293  //
294  // Update velocity state
295  //
296  state.velocity[0] = (float)(last_vel_ned.n * 1.0e-3);
297  state.velocity[1] = (float)(last_vel_ned.e * 1.0e-3);
298  state.velocity[2] = (float)(last_vel_ned.d * 1.0e-3);
299 
300  float ground_vector_sq = state.velocity[0]*state.velocity[0] + state.velocity[1]*state.velocity[1];
301  state.ground_speed = safe_sqrt(ground_vector_sq);
302 
304 
306  powf((float)last_vel_ned.h_accuracy * 1.0e-3f, 2) +
307  powf((float)last_vel_ned.v_accuracy * 1.0e-3f, 2));
309  state.vertical_accuracy = (float) last_pos_llh.v_accuracy * 1.0e-3f;
310 
311  //
312  // Set flags appropriately
313  //
318 
319  //
320  // Update position state
321  //
322  state.location.lat = (int32_t) (last_pos_llh.lat * (double)1e7);
323  state.location.lng = (int32_t) (last_pos_llh.lon * (double)1e7);
324  state.location.alt = (int32_t) (last_pos_llh.height * 100);
326 
327  switch (last_pos_llh.flags.fix_mode) {
328  case 1:
330  break;
331  case 2:
333  break;
334  case 3:
336  break;
337  case 4:
339  break;
340  default:
342  break;
343  }
344 
345  //
346  // Update Internal Timing
347  //
350 
351  return true;
352  }
353  return false;
354 }
355 
356 
357 
358 bool
360 {
361  // This switch reads one character at a time, if we find something that
362  // looks like our preamble we'll try to read the full message length,
363  // calculating the CRC. If the CRC matches, we have an SBP GPS!
364  switch (state.state) {
366  if (data == SBP_PREAMBLE) {
367  state.n_read = 0;
368  state.crc_so_far = 0;
370  }
371  break;
372 
374  *((uint8_t*)&(state.msg_type) + state.n_read) = data;
375  state.crc_so_far = crc16_ccitt(&data, 1, state.crc_so_far);
376  state.n_read += 1;
377  if (state.n_read >= 2) {
378  state.n_read = 0;
380  }
381  break;
382 
384  state.crc_so_far = crc16_ccitt(&data, 1, state.crc_so_far);
385  state.n_read += 1;
386  if (state.n_read >= 2) {
387  state.n_read = 0;
389  }
390  break;
391 
393  state.crc_so_far = crc16_ccitt(&data, 1, state.crc_so_far);
394  state.msg_len = data;
395  state.n_read = 0;
397  break;
398 
400  if (state.msg_type == SBP_HEARTBEAT_MSGTYPE && state.n_read < 4) {
401  *((uint8_t*)&(state.heartbeat_buff) + state.n_read) = data;
402  }
403  state.crc_so_far = crc16_ccitt(&data, 1, state.crc_so_far);
404  state.n_read += 1;
405  if (state.n_read >= state.msg_len) {
406  state.n_read = 0;
408  }
409  break;
410 
412  *((uint8_t*)&(state.crc) + state.n_read) = data;
413  state.n_read += 1;
414  if (state.n_read >= 2) {
416  if (state.crc == state.crc_so_far
417  && state.msg_type == SBP_HEARTBEAT_MSGTYPE) {
418  struct sbp_heartbeat_t* heartbeat = ((struct sbp_heartbeat_t*)state.heartbeat_buff);
419  return heartbeat->protocol_major == 2;
420  }
421  return false;
422  }
423  break;
424 
425  default:
427  break;
428  }
429  return false;
430 }
431 
432 void
434 {
435  if (!should_df_log()) {
436  return;
437  }
438 
439  //TODO: Expand with heartbeat info.
440  //TODO: Get rid of IAR NUM HYPO
441 
442  struct log_SbpHealth pkt = {
448  };
449  DataFlash_Class::instance()->WriteBlock(&pkt, sizeof(pkt));
450 };
451 
452 void
454  uint16_t sender_id,
455  uint8_t msg_len,
456  uint8_t *msg_buff) {
457  if (!should_df_log()) {
458  return;
459  }
460 
461  //MASK OUT MESSAGES WE DON'T WANT TO LOG
462  if (( ((uint16_t) gps._sbp_logmask) & msg_type) == 0) {
463  return;
464  }
465 
466  uint64_t time_us = AP_HAL::micros64();
467  uint8_t pages = 1;
468 
469  if (msg_len > 48) {
470  pages += (msg_len - 48) / 104 + 1;
471  }
472 
473  struct log_SbpRAWH pkt = {
475  time_us : time_us,
476  msg_type : msg_type,
478  index : 1,
479  pages : pages,
480  msg_len : msg_len,
481  };
482  memcpy(pkt.data, msg_buff, MIN(msg_len, 48));
483  DataFlash_Class::instance()->WriteBlock(&pkt, sizeof(pkt));
484 
485  for (uint8_t i = 0; i < pages - 1; i++) {
486  struct log_SbpRAWM pkt2 = {
488  time_us : time_us,
489  msg_type : msg_type,
491  index : uint8_t(i + 2),
492  pages : pages,
493  msg_len : msg_len,
494  };
495  memcpy(pkt2.data, &msg_buff[48 + i * 104], MIN(msg_len - (48 + i * 104), 104));
496  DataFlash_Class::instance()->WriteBlock(&pkt2, sizeof(pkt2));
497  }
498 };
499 
500 void
502  if (!should_df_log()) {
503  return;
504  }
505 
506  struct log_SbpEvent pkt = {
509  wn : last_event.wn,
510  tow : last_event.tow,
514  };
515  DataFlash_Class::instance()->WriteBlock(&pkt, sizeof(pkt));
516 };
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_DOPS_MSGTYPE
Definition: AP_GPS_SBP2.h:72
void logging_log_full_update()
uint16_t msg_type
Definition: LogStructure.h:945
uint8_t level
Definition: LogStructure.h:972
struct PACKED AP_GPS_SBP2::sbp_ext_event_t::flags flags
static const uint8_t SBP_PREAMBLE
Definition: AP_GPS_SBP2.h:66
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
bool _attempt_state_update()
float safe_sqrt(const T v)
Definition: AP_Math.cpp:64
uint32_t last_iar_num_hypotheses
Definition: LogStructure.h:939
uint8_t heartbeat_buff[4]
struct sbp_vel_ned_t last_vel_ned
Definition: AP_GPS_SBP2.h:178
#define Debug(fmt, args ...)
Definition: AP_GPS_SBP2.cpp:48
uint16_t wn
Definition: LogStructure.h:969
GPS_Status status
driver fix status
Definition: AP_GPS.h:132
Interface definition for the various Ground Control System.
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
void logging_log_raw_sbp(uint16_t msg_type, uint16_t sender_id, uint8_t msg_len, uint8_t *msg_buff)
uint8_t index
Definition: LogStructure.h:947
void WriteBlock(const void *pBuffer, uint16_t size)
Definition: DataFlash.cpp:481
struct sbp_heartbeat_t last_heartbeat
Definition: AP_GPS_SBP2.h:174
enum AP_GPS_SBP2::sbp_parser_state_t::@34 state
virtual uint32_t txspace()=0
struct sbp_pos_llh_t last_pos_llh
Definition: AP_GPS_SBP2.h:177
bool read() override
Definition: AP_GPS_SBP2.cpp:72
#define AP_MSEC_PER_WEEK
Definition: definitions.h:96
#define SBP_TIMEOUT_HEARTBEAT
Definition: AP_GPS_SBP2.cpp:37
struct sbp_dops_t last_dops
Definition: AP_GPS_SBP2.h:176
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
uint8_t msg_len
Definition: LogStructure.h:949
#define MIN(a, b)
Definition: usb_conf.h:215
uint32_t crc_error_counter
Definition: AP_GPS_SBP2.h:188
Receiving valid messages and 3D RTK Fixed.
Definition: AP_GPS.h:103
uint32_t last_heartbeat_received_ms
Definition: AP_GPS_SBP2.h:171
uint32_t last_injected_data_ms
Definition: AP_GPS_SBP2.h:172
void _sbp_process()
Definition: AP_GPS_SBP2.cpp:97
AP_GPS & gps
access to frontend (for parameters)
Definition: GPS_Backend.h:70
uint16_t sender_id
Definition: LogStructure.h:958
float wrap_360(const T angle, float unit_mod)
Definition: AP_Math.cpp:123
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_VEL_NED_MSGTYPE
Definition: AP_GPS_SBP2.h:78
Receiving valid messages and 3D lock with differential improvements.
Definition: AP_GPS.h:101
AP_GPS_SBP2(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port)
Definition: AP_GPS_SBP2.cpp:61
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
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_POS_LLH_MSGTYPE
Definition: AP_GPS_SBP2.h:74
static const uint16_t SBP_EXT_EVENT_MSGTYPE
Definition: AP_GPS_SBP2.h:81
#define Info(fmt, args ...)
Definition: AP_GPS_SBP2.cpp:52
virtual size_t write(uint8_t)=0
uint32_t millis()
Definition: system.cpp:157
uint8_t quality
Definition: LogStructure.h:973
static bool _detect(struct SBP2_detect_state &state, uint8_t data)
static DataFlash_Class * instance(void)
Definition: DataFlash.h:62
uint64_t micros64()
Definition: system.cpp:162
struct sbp_ext_event_t last_event
Definition: AP_GPS_SBP2.h:179
uint16_t last_full_update_wn
Definition: AP_GPS_SBP2.h:182
uint64_t time_us
Definition: LogStructure.h:956
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
uint16_t time_week
GPS week number.
Definition: AP_GPS.h:134
enum SBP2_detect_state::@37 state
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
struct PACKED AP_GPS_SBP2::sbp_vel_ned_t::flags flags
uint32_t last_full_update_tow
Definition: AP_GPS_SBP2.h:181
bool should_df_log() const
uint32_t tow
Definition: LogStructure.h:970
uint8_t data[48]
Definition: LogStructure.h:951
uint16_t vdop
vertical dilution of precision in cm
Definition: AP_GPS.h:139
virtual uint32_t available()=0
Location location
last fix location
Definition: AP_GPS.h:135
uint16_t msg_type
Definition: LogStructure.h:957
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
struct PACKED AP_GPS_SBP2::sbp_dops_t::flags flags
struct PACKED AP_GPS_SBP2::sbp_gps_time_t::flags flags
Receiving valid GPS messages but no lock.
Definition: AP_GPS.h:98
static const uint16_t SBP_HEARTBEAT_MSGTYPE
Definition: AP_GPS_SBP2.h:70
void logging_ext_event()
uint8_t data[104]
Definition: LogStructure.h:963
bool have_vertical_accuracy
does GPS give vertical position accuracy? Set to true only once available.
Definition: AP_GPS.h:148
void inject_data(const uint8_t *data, uint16_t len) override
Definition: AP_GPS_SBP2.cpp:84
int32_t ns_residual
Definition: LogStructure.h:971
float speed_accuracy
3D velocity RMS accuracy estimate in m/s
Definition: AP_GPS.h:142
AP_HAL::UARTDriver * port
UART we are attached to.
Definition: GPS_Backend.h:69
bool have_horizontal_accuracy
does GPS give horizontal position accuracy? Set to true only once available.
Definition: AP_GPS.h:147
float horizontal_accuracy
horizontal RMS accuracy estimate in m
Definition: AP_GPS.h:143
float ground_speed
ground speed in m/sec
Definition: AP_GPS.h:136
static const uint16_t SBP_GPS_TIME_MSGTYPE
Definition: AP_GPS_SBP2.h:71
uint64_t time_us
Definition: LogStructure.h:968
struct AP_GPS_SBP2::sbp_parser_state_t parser_state
Receiving valid messages and 3D lock.
Definition: AP_GPS.h:100
#define degrees(x)
Definition: moduletest.c:23
float vertical_accuracy
vertical RMS accuracy estimate in m
Definition: AP_GPS.h:144
int32_t distMod(int32_t tow1_ms, int32_t tow2_ms, int32_t mod)
uint64_t time_us
Definition: LogStructure.h:944
uint8_t msg_len
Definition: LogStructure.h:961
uint16_t hdop
horizontal dilution of precision in cm
Definition: AP_GPS.h:138
#define LOG_PACKET_HEADER_INIT(id)
Definition: LogStructure.h:8
void _sbp_process_message()
struct PACKED AP_GPS_SBP2::sbp_pos_llh_t::flags flags
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
uint8_t num_sats
Number of visible satellites.
Definition: AP_GPS.h:140
bool have_speed_accuracy
does GPS give speed accuracy? Set to true only once available.
Definition: AP_GPS.h:146
float ground_course
ground course in degrees
Definition: AP_GPS.h:137
struct sbp_gps_time_t last_gps_time
Definition: AP_GPS_SBP2.h:175