APM:Libraries
AP_GPS_SBF.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 // Septentrio GPS driver for ArduPilot.
18 // Code by Michael Oborne
19 //
20 
21 #define ALLOW_DOUBLE_MATH_FUNCTIONS
22 
23 #include "AP_GPS.h"
24 #include "AP_GPS_SBF.h"
25 #include <DataFlash/DataFlash.h>
26 #include <GCS_MAVLink/GCS.h>
27 
28 extern const AP_HAL::HAL& hal;
29 
30 #define SBF_DEBUGGING 0
31 
32 #if SBF_DEBUGGING
33  # define Debug(fmt, args ...) \
34 do { \
35  hal.console->printf("%s:%d: " fmt "\n", \
36  __FUNCTION__, __LINE__, \
37  ## args); \
38  hal.scheduler->delay(1); \
39 } while(0)
40 #else
41  # define Debug(fmt, args ...)
42 #endif
43 
44 #define SBF_EXCESS_COMMAND_BYTES 5 // 2 start bytes + validity byte + space byte + endline byte
45 
46 #define RX_ERROR_MASK (CONGESTION | \
47  MISSEDEVENT | \
48  CPUOVERLOAD | \
49  INVALIDCONFIG | \
50  OUTOFGEOFENCE)
51 
52 
54  AP_HAL::UARTDriver *_port) :
55  AP_GPS_Backend(_gps, _state, _port)
56 {
58 
59  port->write((const uint8_t*)_port_enable, strlen(_port_enable));
61 }
62 
63 // Process all bytes available from the stream
64 //
65 bool
67 {
68  bool ret = false;
69  uint32_t available_bytes = port->available();
70  for (uint32_t i = 0; i < available_bytes; i++) {
71  uint8_t temp = port->read();
72  ret |= parse(temp);
73  }
74 
77  uint32_t now = AP_HAL::millis();
78  const char *init_str = _initialisation_blob[_init_blob_index];
79 
80  if (now > _init_blob_time) {
81  if (now > _config_last_ack_time + 2500) {
82  // try to enable input on the GPS port if we have not made progress on configuring it
83  Debug("SBF Sending port enable");
84  port->write((const uint8_t*)_port_enable, strlen(_port_enable));
86  } else {
87  Debug("SBF sending init string: %s", init_str);
88  port->write((const uint8_t*)init_str, strlen(init_str));
89  }
90  _init_blob_time = now + 1000;
91  }
92  } else if (gps._raw_data == 2) { // only manage disarm/rearms when the user opts into it
93  if (hal.util->get_soft_armed()) {
94  _has_been_armed = true;
95  } else if (_has_been_armed && (RxState & SBF_DISK_MOUNTED)) {
96  // since init is done at this point and unmounting should be rate limited,
97  // take over the _init_blob_time variable
98  uint32_t now = AP_HAL::millis();
99  if (now > _init_blob_time) {
100  unmount_disk();
101  _init_blob_time = now + 1000;
102  }
103  }
104  }
105  }
106 
107  return ret;
108 }
109 
110 bool
111 AP_GPS_SBF::parse(uint8_t temp)
112 {
113  switch (sbf_msg.sbf_state)
114  {
115  default:
117  if (temp == SBF_PREAMBLE1) {
119  sbf_msg.read = 0;
120  }
121  break;
123  if (temp == SBF_PREAMBLE2) {
125  } else if (temp == 'R') {
126  Debug("SBF got a response\n");
128  }
129  else
130  {
132  }
133  break;
135  sbf_msg.crc = temp;
137  break;
139  sbf_msg.crc += (uint16_t)(temp << 8);
141  break;
143  sbf_msg.blockid = temp;
145  break;
147  sbf_msg.blockid += (uint16_t)(temp << 8);
149  break;
151  sbf_msg.length = temp;
153  break;
155  sbf_msg.length += (uint16_t)(temp << 8);
157  if (sbf_msg.length % 4 != 0) {
159  Debug("bad packet length=%u\n", (unsigned)sbf_msg.length);
160  }
161  if (sbf_msg.length < 8) {
162  Debug("bad packet length=%u\n", (unsigned)sbf_msg.length);
164  crc_error_counter++; // this is a probable buffer overflow, but this
165  // indicates not enough bytes to do a crc
166  break;
167  }
168  break;
170  if (sbf_msg.read < sizeof(sbf_msg.data)) {
171  sbf_msg.data.bytes[sbf_msg.read] = temp;
172  }
173  sbf_msg.read++;
174  if (sbf_msg.read >= (sbf_msg.length - 8)) {
175  if (sbf_msg.read > sizeof(sbf_msg.data)) {
176  // not interested in these large messages
178  break;
179  }
180  uint16_t crc = crc16_ccitt((uint8_t*)&sbf_msg.blockid, 2, 0);
181  crc = crc16_ccitt((uint8_t*)&sbf_msg.length, 2, crc);
182  crc = crc16_ccitt((uint8_t*)&sbf_msg.data, sbf_msg.length - 8, crc);
183 
185 
186  if (sbf_msg.crc == crc) {
187  return process_message();
188  } else {
189  Debug("crc fail\n");
191  }
192  }
193  break;
195  if (sbf_msg.read < (sizeof(sbf_msg.data) - 1)) {
196  sbf_msg.data.bytes[sbf_msg.read] = temp;
197  } else {
198  // we don't have enough buffer to compare the commands
199  // most probable cause is that a user injected a longer command then
200  // we have buffer for, or it could be a corruption, either way we
201  // simply ignore the result
203  break;
204  }
205  sbf_msg.read++;
206  if (temp == '\n') {
208 
209  // received the result, lets assess it
210  if (sbf_msg.data.bytes[0] == ':') {
211  // valid command, determine if it was the one we were trying
212  // to send in the configuration sequence
214  if (!strncmp(_initialisation_blob[_init_blob_index], (char *)(sbf_msg.data.bytes + 2),
216  Debug("SBF Ack Command: %s\n", sbf_msg.data.bytes);
217  _init_blob_index++;
219  } else {
220  Debug("SBF Ack command (unexpected): %s\n", sbf_msg.data.bytes);
221  }
222  }
223  } else {
224  // rejected command, send it out as a debug
225  Debug("SBF NACK Command: %s\n", sbf_msg.data.bytes);
226  }
227  // resume normal parsing
229  break;
230  }
231  break;
232  }
233 
234  return false;
235 }
236 
237 void
239 {
240  if (!should_df_log()) {
241  return;
242  }
243 
244  uint64_t now = AP_HAL::micros64();
245 
246  struct log_GPS_SBF_EVENT header = {
248  time_us:now,
249  TOW:temp.TOW,
250  WNc:temp.WNc,
251  Mode:temp.Mode,
252  Error:temp.Error,
253  Latitude:ToDeg(temp.Latitude),
254  Longitude:ToDeg(temp.Longitude),
255  Height:temp.Height,
256  Undulation:temp.Undulation,
257  Vn:temp.Vn,
258  Ve:temp.Ve,
259  Vu:temp.Vu,
260  COG:temp.COG
261  };
262 
263  DataFlash_Class::instance()->WriteBlock(&header, sizeof(header));
264 }
265 
266 bool
268 {
269  uint16_t blockid = (sbf_msg.blockid & 8191u);
270 
271  Debug("BlockID %d", blockid);
272 
273  switch (blockid) {
274  case ExtEventPVTGeodetic:
276  break;
277  case PVTGeodetic:
278  {
279  const msg4007 &temp = sbf_msg.data.msg4007u;
280 
281  // Update time state
282  if (temp.WNc != 65535) {
283  state.time_week = temp.WNc;
284  state.time_week_ms = (uint32_t)(temp.TOW);
285  }
286 
288 
289  // Update velocity state (don't use −2·10^10)
290  if (temp.Vn > -200000) {
291  state.velocity.x = (float)(temp.Vn);
292  state.velocity.y = (float)(temp.Ve);
293  state.velocity.z = (float)(-temp.Vu);
294 
296 
297  float ground_vector_sq = state.velocity[0] * state.velocity[0] + state.velocity[1] * state.velocity[1];
298  state.ground_speed = (float)safe_sqrt(ground_vector_sq);
299 
301  state.rtk_age_ms = temp.MeanCorrAge * 10;
302 
303  // value is expressed as twice the rms error = int16 * 0.01/2
304  state.horizontal_accuracy = (float)temp.HAccuracy * 0.005f;
305  state.vertical_accuracy = (float)temp.VAccuracy * 0.005f;
308  }
309 
310  // Update position state (don't use -2·10^10)
311  if (temp.Latitude > -200000) {
312  state.location.lat = (int32_t)(temp.Latitude * RAD_TO_DEG_DOUBLE * (double)1e7);
313  state.location.lng = (int32_t)(temp.Longitude * RAD_TO_DEG_DOUBLE * (double)1e7);
314  state.location.alt = (int32_t)(((float)temp.Height - temp.Undulation) * 1e2f);
315  }
316 
317  if (temp.NrSV != 255) {
318  state.num_sats = temp.NrSV;
319  }
320 
321  Debug("temp.Mode=0x%02x\n", (unsigned)temp.Mode);
322  switch (temp.Mode & 15) {
323  case 0: // no pvt
325  break;
326  case 1: // standalone
328  break;
329  case 2: // dgps
331  break;
332  case 3: // fixed location
334  break;
335  case 4: // rtk fixed
337  break;
338  case 5: // rtk float
340  break;
341  case 6: // sbas
343  break;
344  case 7: // moving rtk fixed
346  break;
347  case 8: // moving rtk float
349  break;
350  }
351 
352  if ((temp.Mode & 64) > 0) { // gps is in base mode
354  } else if ((temp.Mode & 128) > 0) { // gps only has 2d fix
356  }
357 
358  return true;
359  }
360  case DOP:
361  {
362  const msg4001 &temp = sbf_msg.data.msg4001u;
363 
364  state.hdop = temp.HDOP;
365  state.vdop = temp.VDOP;
366  break;
367  }
368  case ReceiverStatus:
369  {
370  const msg4014 &temp = sbf_msg.data.msg4014u;
371  RxState = temp.RxState;
372  if ((RxError & RX_ERROR_MASK) != (temp.RxError & RX_ERROR_MASK)) {
373  gcs().send_text(MAV_SEVERITY_INFO, "GPS %d: SBF error changed (0x%08x/0x%08x)", state.instance + 1,
374  RxError & RX_ERROR_MASK, temp.RxError & RX_ERROR_MASK);
375  }
376  RxError = temp.RxError;
377  break;
378  }
379  case VelCovGeodetic:
380  {
381  const msg5908 &temp = sbf_msg.data.msg5908u;
382 
383  // select the maximum variance, as the EKF will apply it to all the columns in it's estimate
384  // FIXME: Support returning the covariance matrix to the EKF
385  float max_variance_squared = MAX(temp.Cov_VnVn, MAX(temp.Cov_VeVe, temp.Cov_VuVu));
386  if (is_positive(max_variance_squared)) {
387  state.have_speed_accuracy = true;
388  state.speed_accuracy = sqrt(max_variance_squared);
389  } else {
390  state.have_speed_accuracy = false;
391  }
392  break;
393  }
394  }
395 
396  return false;
397 }
398 
400 {
403  gcs().send_text(MAV_SEVERITY_INFO, "GPS %d: SBF is not fully configured (%d/%d)", state.instance + 1,
405  }
406 }
407 
411 }
412 
413 bool AP_GPS_SBF::is_healthy (void) const {
414  return (RxError & RX_ERROR_MASK) == 0;
415 }
416 
417 void AP_GPS_SBF::mount_disk (void) const {
418  const char* command = "emd, DSK1, Mount\n";
419  Debug("Mounting disk");
420  port->write((const uint8_t*)command, strlen(command));
421 }
422 
423 void AP_GPS_SBF::unmount_disk (void) const {
424  const char* command = "emd, DSK1, Unmount\n";
425  Debug("Unmounting disk");
426  port->write((const uint8_t*)command, strlen(command));
427 }
428 
430  bool is_logging = true; // assume that its logging until proven otherwise
431  if (gps._raw_data) {
432  if (!(RxState & SBF_DISK_MOUNTED)){
433  is_logging = false;
434  gcs().send_text(MAV_SEVERITY_INFO, "GPS %d: SBF disk is not mounted", state.instance + 1);
435 
436  // simply attempt to mount the disk, no need to check if the command was
437  // ACK/NACK'd as we don't continuously attempt to remount the disk
438  gcs().send_text(MAV_SEVERITY_INFO, "GPS %d: Attempting to mount disk", state.instance + 1);
439  mount_disk();
440  // reset the flag to indicate if we should be logging
441  _has_been_armed = false;
442  }
443  else if (RxState & SBF_DISK_FULL) {
444  is_logging = false;
445  gcs().send_text(MAV_SEVERITY_INFO, "GPS %d: SBF disk is full", state.instance + 1);
446  }
447  else if (!(RxState & SBF_DISK_ACTIVITY)) {
448  is_logging = false;
449  gcs().send_text(MAV_SEVERITY_INFO, "GPS %d: SBF is not currently logging", state.instance + 1);
450  }
451  }
452 
453  return is_logging;
454 }
bool get_soft_armed() const
Definition: Util.h:15
Definition: AP_GPS.h:48
uint32_t time_week_ms
GPS time (milliseconds from start of GPS week)
Definition: AP_GPS.h:133
const char * _initialisation_blob[5]
Definition: AP_GPS_SBF.h:64
uint32_t last_gps_time_ms
the system time we got the last GPS timestamp, milliseconds
Definition: AP_GPS.h:149
uint16_t MeanCorrAge
Definition: AP_GPS_SBF.h:111
float safe_sqrt(const T v)
Definition: AP_Math.cpp:64
const char * _port_enable
Definition: AP_GPS_SBF.h:72
uint8_t _init_blob_index
Definition: AP_GPS_SBF.h:62
uint8_t instance
Definition: AP_GPS.h:129
GPS_Status status
driver fix status
Definition: AP_GPS.h:132
struct AP_GPS_SBF::sbf_msg_parser_t sbf_msg
Interface definition for the various Ground Control System.
uint32_t RxState
Definition: AP_GPS_SBF.h:75
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
AP_HAL::Util * util
Definition: HAL.h:115
void WriteBlock(const void *pBuffer, uint16_t size)
Definition: DataFlash.cpp:481
GCS & gcs()
bool is_positive(const T fVal1)
Definition: AP_Math.h:50
#define SBF_DISK_ACTIVITY
Definition: AP_GPS_SBF.h:26
bool process_message()
Definition: AP_GPS_SBF.cpp:267
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
#define ToDeg(x)
Definition: AP_Common.h:54
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
Receiving valid messages and 3D RTK Fixed.
Definition: AP_GPS.h:103
#define RX_ERROR_MASK
Definition: AP_GPS_SBF.cpp:46
void log_ExtEventPVTGeodetic(const msg4007 &temp)
Definition: AP_GPS_SBF.cpp:238
uint32_t crc_error_counter
Definition: AP_GPS_SBF.h:74
void mount_disk(void) const
Definition: AP_GPS_SBF.cpp:417
AP_GPS & gps
access to frontend (for parameters)
Definition: GPS_Backend.h:70
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
Receiving valid messages and 3D lock with differential improvements.
Definition: AP_GPS.h:101
Receiving valid messages and 3D RTK Float.
Definition: AP_GPS.h:102
T y
Definition: vector3.h:67
virtual size_t write(uint8_t)=0
uint32_t millis()
Definition: system.cpp:157
bool parse(uint8_t temp)
Definition: AP_GPS_SBF.cpp:111
#define Debug(fmt, args ...)
Definition: AP_GPS_SBF.cpp:41
AP_GPS_SBF(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port)
Definition: AP_GPS_SBF.cpp:53
enum AP_GPS_SBF::sbf_msg_parser_t::@32 sbf_state
static DataFlash_Class * instance(void)
Definition: DataFlash.h:62
T z
Definition: vector3.h:67
uint64_t micros64()
Definition: system.cpp:162
void unmount_disk(void) const
Definition: AP_GPS_SBF.cpp:423
bool _has_been_armed
Definition: AP_GPS_SBF.h:80
uint16_t time_week
GPS week number.
Definition: AP_GPS.h:134
Receiving valid messages and 2D lock.
Definition: AP_GPS.h:99
uint32_t rtk_age_ms
GPS age of last baseline correction in milliseconds (0 when no corrections, 0xFFFFFFFF indicates over...
Definition: AP_GPS.h:154
AP_GPS::GPS_State & state
public state for this instance
Definition: GPS_Backend.h:71
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
virtual int16_t read()=0
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
bool should_df_log() const
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
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
bool read()
Definition: AP_GPS_SBF.cpp:66
Receiving valid GPS messages but no lock.
Definition: AP_GPS.h:98
uint32_t _init_blob_time
Definition: AP_GPS_SBF.h:63
bool is_configured(void) override
Definition: AP_GPS_SBF.cpp:408
AP_Int8 _raw_data
Definition: AP_GPS.h:431
static const uint8_t SBF_PREAMBLE1
Definition: AP_GPS_SBF.h:59
AP_Int8 _auto_config
Definition: AP_GPS.h:435
#define SBF_DISK_FULL
Definition: AP_GPS_SBF.h:27
#define SBF_EXCESS_COMMAND_BYTES
Definition: AP_GPS_SBF.cpp:44
bool have_vertical_accuracy
does GPS give vertical position accuracy? Set to true only once available.
Definition: AP_GPS.h:148
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
void broadcast_configuration_failure_reason(void) const override
Definition: AP_GPS_SBF.cpp:399
float ground_speed
ground speed in m/sec
Definition: AP_GPS.h:136
static const uint8_t SBF_PREAMBLE2
Definition: AP_GPS_SBF.h:60
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
uint8_t bytes[256]
Definition: AP_GPS_SBF.h:173
uint32_t RxError
Definition: AP_GPS_SBF.h:76
uint32_t _config_last_ack_time
Definition: AP_GPS_SBF.h:70
uint16_t hdop
horizontal dilution of precision in cm
Definition: AP_GPS.h:138
#define LOG_PACKET_HEADER_INIT(id)
Definition: LogStructure.h:8
bool prepare_for_arming(void) override
Definition: AP_GPS_SBF.cpp:429
uint16_t crc16_ccitt(const uint8_t *buf, uint32_t len, uint16_t crc)
Definition: edc.cpp:52
T x
Definition: vector3.h:67
#define SBF_DISK_MOUNTED
Definition: AP_GPS_SBF.h:28
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
bool is_healthy(void) const override
Definition: AP_GPS_SBF.cpp:413