APM:Libraries
AP_GPS_ERB.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  // Emlid Reach Binary (ERB) GPS driver for ArduPilot.
18  // ERB protocol: http://files.emlid.com/ERB.pdf
19 
20 #include "AP_GPS.h"
21 #include "AP_GPS_ERB.h"
22 
23 #define ERB_DEBUGGING 0
24 
25 #define STAT_FIX_VALID 0x01
26 
27 extern const AP_HAL::HAL& hal;
28 
29 #if ERB_DEBUGGING
30  # define Debug(fmt, args ...) do {hal.console->printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); hal.scheduler->delay(1); } while(0)
31 #else
32  # define Debug(fmt, args ...)
33 #endif
34 
36  AP_GPS_Backend(_gps, _state, _port),
37  next_fix(AP_GPS::NO_FIX)
38 {
39 }
40 
41 // Process bytes available from the stream
42 //
43 // The stream is assumed to contain only messages we recognise. If it
44 // contains other messages, and those messages contain the preamble
45 // bytes, it is possible for this code to fail to synchronise to the
46 // stream immediately. Without buffering the entire message and
47 // re-processing it from the top, this is unavoidable. The parser
48 // attempts to avoid this when possible.
49 //
50 bool
52 {
53  uint8_t data;
54  int16_t numc;
55  bool parsed = false;
56 
57  numc = port->available();
58  for (int16_t i = 0; i < numc; i++) { // Process bytes received
59 
60  // read the next byte
61  data = port->read();
62 
63  reset:
64  switch(_step) {
65 
66  // Message preamble detection
67  //
68  case 1:
69  if (PREAMBLE2 == data) {
70  _step++;
71  break;
72  }
73  _step = 0;
74  Debug("reset %u", __LINE__);
76  case 0:
77  if(PREAMBLE1 == data)
78  _step++;
79  break;
80 
81  // Message header processing
82  //
83  case 2:
84  _step++;
85  _msg_id = data;
86  _ck_b = _ck_a = data; // reset the checksum accumulators
87  break;
88  case 3:
89  _step++;
90  _ck_b += (_ck_a += data); // checksum byte
91  _payload_length = data; // payload length low byte
92  break;
93  case 4:
94  _step++;
95  _ck_b += (_ck_a += data); // checksum byte
96  _payload_length += (uint16_t)(data<<8);
97  _payload_counter = 0; // prepare to receive payload
98  break;
99 
100  // Receive message data
101  //
102  case 5:
103  _ck_b += (_ck_a += data); // checksum byte
104  if (_payload_counter < sizeof(_buffer)) {
105  _buffer[_payload_counter] = data;
106  }
108  _step++;
109  break;
110 
111  // Checksum and message processing
112  //
113  case 6:
114  _step++;
115  if (_ck_a != data) {
116  Debug("bad cka %x should be %x", data, _ck_a);
117  _step = 0;
118  goto reset;
119  }
120  break;
121  case 7:
122  _step = 0;
123  if (_ck_b != data) {
124  Debug("bad ckb %x should be %x", data, _ck_b);
125  break; // bad checksum
126  }
127 
128  if (_parse_gps()) {
129  parsed = true;
130  }
131  break;
132  }
133  }
134  return parsed;
135 }
136 
137 bool
139 {
140  switch (_msg_id) {
141  case MSG_VER:
142  Debug("Version of ERB protocol %u.%u.%u",
146  break;
147  case MSG_POS:
148  Debug("Message POS");
150  state.location.lng = (int32_t)(_buffer.pos.longitude * (double)1e7);
151  state.location.lat = (int32_t)(_buffer.pos.latitude * (double)1e7);
152  state.location.alt = (int32_t)(_buffer.pos.altitude_msl * 100);
154  _new_position = true;
159  break;
160  case MSG_STAT:
161  Debug("Message STAT fix_status=%u fix_type=%u",
167  } else if (_buffer.stat.fix_type == AP_GPS_ERB::FIX_FLOAT) {
171  } else {
174  }
175  } else {
178  }
184  }
185  break;
186  case MSG_DOPS:
187  Debug("Message DOPS");
190  break;
191  case MSG_VEL:
192  Debug("Message VEL");
194  state.ground_speed = _buffer.vel.speed_2d * 0.01f; // m/s
195  // Heading 2D deg * 100000 rescaled to deg * 100
198  state.velocity.x = _buffer.vel.vel_north * 0.01f;
199  state.velocity.y = _buffer.vel.vel_east * 0.01f;
200  state.velocity.z = _buffer.vel.vel_down * 0.01f;
201  state.have_speed_accuracy = true;
203  _new_speed = true;
204  break;
205  case MSG_RTK:
206  Debug("Message RTK");
207  state.rtk_baseline_coords_type = RTK_BASELINE_COORDINATE_SYSTEM_NED;
209  if (_buffer.rtk.age_cs == 0xFFFF) {
210  state.rtk_age_ms = 0xFFFFFFFF;
211  } else {
213  }
218 
221  break;
222  default:
223  Debug("Unexpected message 0x%02x", (unsigned)_msg_id);
224  return false;
225  }
226  // we only return true when we get new position and speed data
227  // this ensures we don't use stale data
229  _new_speed = _new_position = false;
230  _fix_count++;
231  return true;
232  }
233  return false;
234 }
235 
236 /*
237  detect a ERB GPS. Adds one byte, and returns true if the stream
238  matches a ERB
239  */
240 bool
242 {
243 reset:
244  switch (state.step) {
245  case 1:
246  if (PREAMBLE2 == data) {
247  state.step++;
248  break;
249  }
250  state.step = 0;
251  FALLTHROUGH;
252  case 0:
253  if (PREAMBLE1 == data)
254  state.step++;
255  break;
256  case 2:
257  state.step++;
258  state.ck_b = state.ck_a = data;
259  break;
260  case 3:
261  state.step++;
262  state.ck_b += (state.ck_a += data);
263  state.payload_length = data;
264  break;
265  case 4:
266  state.step++;
267  state.ck_b += (state.ck_a += data);
268  state.payload_counter = 0;
269  break;
270  case 5:
271  state.ck_b += (state.ck_a += data);
272  if (++state.payload_counter == state.payload_length)
273  state.step++;
274  break;
275  case 6:
276  state.step++;
277  if (state.ck_a != data) {
278  state.step = 0;
279  goto reset;
280  }
281  break;
282  case 7:
283  state.step = 0;
284  if (state.ck_b == data) {
285  return true;
286  } else {
287  goto reset;
288  }
289  }
290  return false;
291 }
uint16_t _payload_length
Definition: AP_GPS_ERB.h:135
bool read()
Definition: AP_GPS_ERB.cpp:51
uint32_t speed_2d
Ground speed (2-D) [cm/s].
Definition: AP_GPS_ERB.h:84
Definition: AP_GPS.h:48
uint32_t time_week_ms
GPS time (milliseconds from start of GPS week)
Definition: AP_GPS.h:133
uint32_t time
GPS time of week of the navigation epoch [ms].
Definition: AP_GPS_ERB.h:80
uint8_t base_num_sats
Current number of satellites used for RTK calculation.
Definition: AP_GPS_ERB.h:89
uint16_t rtk_week_number
GPS Week Number of last baseline.
Definition: AP_GPS.h:153
uint32_t last_gps_time_ms
the system time we got the last GPS timestamp, milliseconds
Definition: AP_GPS.h:149
uint8_t _step
Definition: AP_GPS_ERB.h:133
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
#define FALLTHROUGH
Definition: AP_Common.h:50
bool _new_speed
Definition: AP_GPS_ERB.h:147
GPS_Status status
driver fix status
Definition: AP_GPS.h:132
bool have_vertical_velocity
does GPS give vertical velocity? Set to true only once available.
Definition: AP_GPS.h:145
int32_t rtk_baseline_z_mm
Current baseline in ECEF z or NED down component in mm.
Definition: AP_GPS.h:159
Vector3f velocity
3D velocity in m/s, in NED format
Definition: AP_GPS.h:141
int32_t heading_2d
Heading of motion 2-D [1e5 deg].
Definition: AP_GPS_ERB.h:85
uint32_t vertical_accuracy
Vertical accuracy estimate [mm].
Definition: AP_GPS_ERB.h:63
uint8_t _ck_b
Definition: AP_GPS_ERB.h:130
bool _new_position
Definition: AP_GPS_ERB.h:145
void reset()
uint32_t speed_accuracy
Speed accuracy Estimate [cm/s].
Definition: AP_GPS_ERB.h:86
uint32_t time
GPS time of week of the navigation epoch [ms].
Definition: AP_GPS_ERB.h:57
int32_t baseline_N_mm
distance between base and rover along the north axis in millimeters
Definition: AP_GPS_ERB.h:91
int32_t vel_down
Down velocity component [cm/s].
Definition: AP_GPS_ERB.h:83
uint8_t fix_type
see erb_fix_type enum
Definition: AP_GPS_ERB.h:68
#define Debug(fmt, args ...)
Definition: AP_GPS_ERB.cpp:32
uint32_t _last_vel_time
Definition: AP_GPS_ERB.h:142
uint16_t base_week_number
GPS Week Number of last baseline.
Definition: AP_GPS_ERB.h:95
static bool _detect(struct ERB_detect_state &state, uint8_t data)
Definition: AP_GPS_ERB.cpp:241
int32_t baseline_D_mm
distance between base and rover along the down axis in millimeters
Definition: AP_GPS_ERB.h:93
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
uint8_t _ck_a
Definition: AP_GPS_ERB.h:129
int32_t rtk_baseline_y_mm
Current baseline in ECEF y or NED east component in mm.
Definition: AP_GPS.h:158
bool _parse_gps()
Definition: AP_GPS_ERB.cpp:138
Receiving valid messages and 3D RTK Fixed.
Definition: AP_GPS.h:103
uint16_t ar_ratio
AR ratio multiplied by 10.
Definition: AP_GPS_ERB.h:94
uint16_t vDOP
Vertical DOP.
Definition: AP_GPS_ERB.h:76
double altitude_msl
Height above mean sea level [m].
Definition: AP_GPS_ERB.h:61
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
uint16_t _payload_counter
Definition: AP_GPS_ERB.h:136
#define f(i)
uint8_t rtk_num_sats
Current number of satellites used for RTK calculation.
Definition: AP_GPS.h:155
uint8_t _fix_count
Definition: AP_GPS_ERB.h:139
uint32_t _last_pos_time
Definition: AP_GPS_ERB.h:141
uint32_t horizontal_accuracy
Horizontal accuracy estimate [mm].
Definition: AP_GPS_ERB.h:62
Receiving valid messages and 3D RTK Float.
Definition: AP_GPS.h:102
T y
Definition: vector3.h:67
AP_GPS::GPS_Status next_fix
Definition: AP_GPS_ERB.h:153
uint32_t millis()
Definition: system.cpp:157
uint8_t rtk_baseline_coords_type
Coordinate system of baseline. 0 == ECEF, 1 == NED.
Definition: AP_GPS.h:156
T z
Definition: vector3.h:67
uint16_t time_week
GPS week number.
Definition: AP_GPS.h:134
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
union AP_GPS_ERB::PACKED _buffer
AP_GPS::GPS_State & state
public state for this instance
Definition: GPS_Backend.h:71
virtual int16_t read()=0
DEFINE_BYTE_ARRAY_METHODS erb_ver ver
Definition: AP_GPS_ERB.h:102
uint32_t time
GPS time of week of the navigation epoch [ms].
Definition: AP_GPS_ERB.h:66
#define STAT_FIX_VALID
Definition: AP_GPS_ERB.cpp:25
uint16_t vdop
vertical dilution of precision in cm
Definition: AP_GPS.h:139
uint32_t rtk_accuracy
Current estimate of 3D baseline accuracy (receiver dependent, typical 0 to 9999)
Definition: AP_GPS.h:160
virtual uint32_t available()=0
Location location
last fix location
Definition: AP_GPS.h:135
uint16_t hDOP
Horizontal DOP.
Definition: AP_GPS_ERB.h:77
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
AP_GPS_ERB(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port)
Definition: AP_GPS_ERB.cpp:35
Receiving valid GPS messages but no lock.
Definition: AP_GPS.h:98
int32_t baseline_E_mm
distance between base and rover along the east axis in millimeters
Definition: AP_GPS_ERB.h:92
uint32_t rtk_time_week_ms
GPS Time of Week of last baseline in milliseconds.
Definition: AP_GPS.h:152
uint32_t base_time_week_ms
GPS Time of Week of last baseline in milliseconds.
Definition: AP_GPS_ERB.h:96
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
float ground_speed
ground speed in m/sec
Definition: AP_GPS.h:136
Receiving valid messages and 3D lock.
Definition: AP_GPS.h:100
float vertical_accuracy
vertical RMS accuracy estimate in m
Definition: AP_GPS.h:144
uint8_t _msg_id
Definition: AP_GPS_ERB.h:134
uint16_t hdop
horizontal dilution of precision in cm
Definition: AP_GPS.h:138
uint16_t age_cs
Age of the corrections in centiseconds (0 when no corrections, 0xFFFF indicates overflow) ...
Definition: AP_GPS_ERB.h:90
T x
Definition: vector3.h:67
uint8_t num_sats
Number of visible satellites.
Definition: AP_GPS.h:140
int32_t vel_north
North velocity component [cm/s].
Definition: AP_GPS_ERB.h:81
int32_t vel_east
East velocity component [cm/s].
Definition: AP_GPS_ERB.h:82
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
int32_t rtk_baseline_x_mm
Current baseline in ECEF x or NED north component in mm.
Definition: AP_GPS.h:157