APM:Libraries
AP_GPS_GSOF.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 // Trimble 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_GSOF.h"
25 #include <DataFlash/DataFlash.h>
26 
27 extern const AP_HAL::HAL& hal;
28 
29 #define gsof_DEBUGGING 0
30 
31 #if gsof_DEBUGGING
32 # define Debug(fmt, args ...) \
33 do { \
34  hal.console->printf("%s:%d: " fmt "\n", \
35  __FUNCTION__, __LINE__, \
36  ## args); \
37  hal.scheduler->delay(1); \
38 } while(0)
39 #else
40 # define Debug(fmt, args ...)
41 #endif
42 
44  AP_HAL::UARTDriver *_port) :
45  AP_GPS_Backend(_gps, _state, _port)
46 {
48 
49  // baud request for port 0
50  requestBaud(0);
51  // baud request for port 3
52  requestBaud(3);
53 
54  uint32_t now = AP_HAL::millis();
55  gsofmsg_time = now + 110;
56 }
57 
58 // Process all bytes available from the stream
59 //
60 bool
62 {
63  uint32_t now = AP_HAL::millis();
64 
65  if (gsofmsgreq_index < (sizeof(gsofmsgreq))) {
66  if (now > gsofmsg_time) {
68  requestGSOF(gsofmsgreq[gsofmsgreq_index], 3);
69  gsofmsg_time = now + 110;
70  gsofmsgreq_index++;
71  }
72  }
73 
74  bool ret = false;
75  while (port->available() > 0) {
76  uint8_t temp = port->read();
77  ret |= parse(temp);
78  }
79 
80  return ret;
81 }
82 
83 bool
84 AP_GPS_GSOF::parse(uint8_t temp)
85 {
86  switch (gsof_msg.gsof_state)
87  {
88  default:
90  if (temp == GSOF_STX)
91  {
92  gsof_msg.starttx = temp;
94  gsof_msg.read = 0;
96  }
97  break;
99  gsof_msg.status = temp;
101  gsof_msg.checksumcalc += temp;
102  break;
104  gsof_msg.packettype = temp;
106  gsof_msg.checksumcalc += temp;
107  break;
109  gsof_msg.length = temp;
111  gsof_msg.checksumcalc += temp;
112  break;
114  gsof_msg.data[gsof_msg.read] = temp;
115  gsof_msg.read++;
116  gsof_msg.checksumcalc += temp;
117  if (gsof_msg.read >= gsof_msg.length)
118  {
120  }
121  break;
123  gsof_msg.checksum = temp;
126  {
127  return process_message();
128  }
129  break;
131  gsof_msg.endtx = temp;
133  break;
134  }
135 
136  return false;
137 }
138 
139 void
140 AP_GPS_GSOF::requestBaud(uint8_t portindex)
141 {
142  uint8_t buffer[19] = {0x02,0x00,0x64,0x0d,0x00,0x00,0x00, // application file record
143  0x03, 0x00, 0x01, 0x00, // file control information block
144  0x02, 0x04, portindex, 0x07, 0x00,0x00, // serial port baud format
145  0x00,0x03
146  }; // checksum
147 
148  buffer[4] = packetcount++;
149 
150  uint8_t checksum = 0;
151  for (uint8_t a = 1; a < (sizeof(buffer) - 1); a++) {
152  checksum += buffer[a];
153  }
154 
155  buffer[17] = checksum;
156 
157  port->write((const uint8_t*)buffer, sizeof(buffer));
158 }
159 
160 void
161 AP_GPS_GSOF::requestGSOF(uint8_t messagetype, uint8_t portindex)
162 {
163  uint8_t buffer[21] = {0x02,0x00,0x64,0x0f,0x00,0x00,0x00, // application file record
164  0x03,0x00,0x01,0x00, // file control information block
165  0x07,0x06,0x0a,portindex,0x01,0x00,0x01,0x00, // output message record
166  0x00,0x03
167  }; // checksum
168 
169  buffer[4] = packetcount++;
170  buffer[17] = messagetype;
171 
172  uint8_t checksum = 0;
173  for (uint8_t a = 1; a < (sizeof(buffer) - 1); a++) {
174  checksum += buffer[a];
175  }
176 
177  buffer[19] = checksum;
178 
179  port->write((const uint8_t*)buffer, sizeof(buffer));
180 }
181 
182 double
183 AP_GPS_GSOF::SwapDouble(uint8_t* src, uint32_t pos)
184 {
185  union {
186  double d;
187  char bytes[sizeof(double)];
188  } doubleu;
189  doubleu.bytes[0] = src[pos + 7];
190  doubleu.bytes[1] = src[pos + 6];
191  doubleu.bytes[2] = src[pos + 5];
192  doubleu.bytes[3] = src[pos + 4];
193  doubleu.bytes[4] = src[pos + 3];
194  doubleu.bytes[5] = src[pos + 2];
195  doubleu.bytes[6] = src[pos + 1];
196  doubleu.bytes[7] = src[pos + 0];
197 
198  return doubleu.d;
199 }
200 
201 float
202 AP_GPS_GSOF::SwapFloat(uint8_t* src, uint32_t pos)
203 {
204  union {
205  float f;
206  char bytes[sizeof(float)];
207  } floatu;
208  floatu.bytes[0] = src[pos + 3];
209  floatu.bytes[1] = src[pos + 2];
210  floatu.bytes[2] = src[pos + 1];
211  floatu.bytes[3] = src[pos + 0];
212 
213  return floatu.f;
214 }
215 
216 uint32_t
217 AP_GPS_GSOF::SwapUint32(uint8_t* src, uint32_t pos)
218 {
219  union {
220  uint32_t u;
221  char bytes[sizeof(uint32_t)];
222  } uint32u;
223  uint32u.bytes[0] = src[pos + 3];
224  uint32u.bytes[1] = src[pos + 2];
225  uint32u.bytes[2] = src[pos + 1];
226  uint32u.bytes[3] = src[pos + 0];
227 
228  return uint32u.u;
229 }
230 
231 uint16_t
232 AP_GPS_GSOF::SwapUint16(uint8_t* src, uint32_t pos)
233 {
234  union {
235  uint16_t u;
236  char bytes[sizeof(uint16_t)];
237  } uint16u;
238  uint16u.bytes[0] = src[pos + 1];
239  uint16u.bytes[1] = src[pos + 0];
240 
241  return uint16u.u;
242 }
243 
244 bool
246 {
247  //http://www.trimble.com/OEM_ReceiverHelp/V4.81/en/default.html#welcome.html
248 
249  if (gsof_msg.packettype == 0x40) { // GSOF
250 #if gsof_DEBUGGING
251  uint8_t trans_number = gsof_msg.data[0];
252  uint8_t pageidx = gsof_msg.data[1];
253  uint8_t maxpageidx = gsof_msg.data[2];
254 
255  Debug("GSOF page: %u of %u (trans_number=%u)",
256  pageidx, maxpageidx, trans_number);
257 #endif
258 
259  int valid = 0;
260 
261  // want 1 2 8 9 12
262  for (uint32_t a = 3; a < gsof_msg.length; a++)
263  {
264  uint8_t output_type = gsof_msg.data[a];
265  a++;
266  uint8_t output_length = gsof_msg.data[a];
267  a++;
268  //Debug("GSOF type: " + output_type + " len: " + output_length);
269 
270  if (output_type == 1) // pos time
271  {
274  state.num_sats = gsof_msg.data[a + 6];
275  uint8_t posf1 = gsof_msg.data[a + 7];
276  uint8_t posf2 = gsof_msg.data[a + 8];
277 
278  //Debug("POSTIME: " + posf1 + " " + posf2);
279 
280  if ((posf1 & 1)) { // New position
282  if ((posf2 & 1)) { // Differential position
284  if (posf2 & 2) { // Differential position method
285  if (posf2 & 4) {// Differential position method
287  } else {
289  }
290  }
291  }
292  } else {
294  }
295  valid++;
296  }
297  else if (output_type == 2) // position
298  {
299  state.location.lat = (int32_t)(RAD_TO_DEG_DOUBLE * (SwapDouble(gsof_msg.data, a)) * (double)1e7);
300  state.location.lng = (int32_t)(RAD_TO_DEG_DOUBLE * (SwapDouble(gsof_msg.data, a + 8)) * (double)1e7);
301  state.location.alt = (int32_t)(SwapDouble(gsof_msg.data, a + 16) * 100);
302 
304 
305  valid++;
306  }
307  else if (output_type == 8) // velocity
308  {
309  uint8_t vflag = gsof_msg.data[a];
310  if ((vflag & 1) == 1)
311  {
315  state.velocity.z = -SwapFloat(gsof_msg.data, a + 9);
317  }
318  valid++;
319  }
320  else if (output_type == 9) //dop
321  {
322  state.hdop = (uint16_t)(SwapFloat(gsof_msg.data, a + 4) * 100);
323  valid++;
324  }
325  else if (output_type == 12) // position sigma
326  {
331  valid++;
332  }
333 
334  a += output_length-1u;
335  }
336 
337  if (valid == 5) {
338  return true;
339  } else {
341  }
342  }
343 
344  return false;
345 }
346 
Definition: AP_GPS.h:48
uint32_t time_week_ms
GPS time (milliseconds from start of GPS week)
Definition: AP_GPS.h:133
uint8_t packetcount
Definition: AP_GPS_GSOF.h:79
uint32_t last_gps_time_ms
the system time we got the last GPS timestamp, milliseconds
Definition: AP_GPS.h:149
enum AP_GPS_GSOF::gsof_msg_parser_t::@28 gsof_state
float SwapFloat(uint8_t *src, uint32_t pos)
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
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
Vector3f velocity
3D velocity in m/s, in NED format
Definition: AP_GPS.h:141
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
Receiving valid messages and 3D RTK Fixed.
Definition: AP_GPS.h:103
void requestGSOF(uint8_t messagetype, uint8_t portindex)
void requestBaud(uint8_t portindex)
AP_GPS_GSOF(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port)
Definition: AP_GPS_GSOF.cpp:43
#define Debug(fmt, args ...)
Definition: AP_GPS_GSOF.cpp:40
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
bool parse(uint8_t temp)
Definition: AP_GPS_GSOF.cpp:84
uint8_t gsofmsgreq_index
Definition: AP_GPS_GSOF.h:82
#define f(i)
Receiving valid messages and 3D RTK Float.
Definition: AP_GPS.h:102
bool process_message()
virtual size_t write(uint8_t)=0
uint32_t millis()
Definition: system.cpp:157
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
T z
Definition: vector3.h:67
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
static const uint8_t GSOF_STX
Definition: AP_GPS_GSOF.h:76
virtual int16_t read()=0
uint32_t SwapUint32(uint8_t *src, uint32_t pos)
struct AP_GPS_GSOF::gsof_msg_parser_t gsof_msg
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
void fill_3d_velocity(void)
Receiving valid GPS messages but no lock.
Definition: AP_GPS.h:98
uint16_t SwapUint16(uint8_t *src, uint32_t pos)
bool have_vertical_accuracy
does GPS give vertical position accuracy? Set to true only once available.
Definition: AP_GPS.h:148
AP_HAL::UARTDriver * port
UART we are attached to.
Definition: GPS_Backend.h:69
double SwapDouble(uint8_t *src, uint32_t pos)
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
#define degrees(x)
Definition: moduletest.c:23
float vertical_accuracy
vertical RMS accuracy estimate in m
Definition: AP_GPS.h:144
uint16_t hdop
horizontal dilution of precision in cm
Definition: AP_GPS.h:138
uint8_t gsofmsgreq[5]
Definition: AP_GPS_GSOF.h:83
uint32_t gsofmsg_time
Definition: AP_GPS_GSOF.h:81
uint8_t num_sats
Number of visible satellites.
Definition: AP_GPS.h:140
float ground_course
ground course in degrees
Definition: AP_GPS.h:137