APM:Libraries
AP_GPS_GSOF.h
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 #pragma once
21 
22 #include "AP_GPS.h"
23 #include "GPS_Backend.h"
24 
26 {
27 public:
29 
32  }
33 
34  // Methods
35  bool read();
36 
37  const char *name() const override { return "GSOF"; }
38 
39 private:
40 
41  bool parse(uint8_t temp);
42  bool process_message();
43  void requestBaud(uint8_t portindex);
44  void requestGSOF(uint8_t messagetype, uint8_t portindex);
45  double SwapDouble(uint8_t* src, uint32_t pos);
46  float SwapFloat(uint8_t* src, uint32_t pos);
47  uint32_t SwapUint32(uint8_t* src, uint32_t pos);
48  uint16_t SwapUint16(uint8_t* src, uint32_t pos);
49 
50 
52  {
53  enum
54  {
55  STARTTX = 0,
62  } gsof_state;
63 
64  uint8_t starttx;
65  uint8_t status;
66  uint8_t packettype;
67  uint8_t length;
68  uint8_t data[256];
69  uint8_t checksum;
70  uint8_t endtx;
71 
72  uint16_t read;
73  uint8_t checksumcalc;
74  } gsof_msg;
75 
76  static const uint8_t GSOF_STX = 0x02;
77  static const uint8_t GSOF_ETX = 0x03;
78 
79  uint8_t packetcount = 0;
80 
81  uint32_t gsofmsg_time = 0;
82  uint8_t gsofmsgreq_index = 0;
83  uint8_t gsofmsgreq[5] = {1,2,8,9,12};
84 };
Definition: AP_GPS.h:48
uint8_t packetcount
Definition: AP_GPS_GSOF.h:79
enum AP_GPS_GSOF::gsof_msg_parser_t::@28 gsof_state
float SwapFloat(uint8_t *src, uint32_t pos)
Receiving valid messages and 3D RTK Fixed.
Definition: AP_GPS.h:103
void requestGSOF(uint8_t messagetype, uint8_t portindex)
GPS_Status
GPS status codes.
Definition: AP_GPS.h:96
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
bool parse(uint8_t temp)
Definition: AP_GPS_GSOF.cpp:84
uint8_t gsofmsgreq_index
Definition: AP_GPS_GSOF.h:82
static const uint8_t GSOF_ETX
Definition: AP_GPS_GSOF.h:77
bool process_message()
static const uint8_t GSOF_STX
Definition: AP_GPS_GSOF.h:76
AP_GPS::GPS_Status highest_supported_status(void)
Definition: AP_GPS_GSOF.h:30
uint32_t SwapUint32(uint8_t *src, uint32_t pos)
struct AP_GPS_GSOF::gsof_msg_parser_t gsof_msg
const char * name() const override
Definition: AP_GPS_GSOF.h:37
uint16_t SwapUint16(uint8_t *src, uint32_t pos)
double SwapDouble(uint8_t *src, uint32_t pos)
uint8_t gsofmsgreq[5]
Definition: AP_GPS_GSOF.h:83
uint32_t gsofmsg_time
Definition: AP_GPS_GSOF.h:81