APM:Libraries
AP_GPS_SIRF.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 // SiRF Binary GPS driver for ArduPilot and ArduPilotMega.
18 // Code by Michael Smith.
19 //
20 #pragma once
21 
22 #include <AP_Common/AP_Common.h>
23 #include <AP_HAL/AP_HAL.h>
24 
25 #include "AP_GPS.h"
26 #include "GPS_Backend.h"
27 
28 #define SIRF_SET_BINARY "$PSRF100,0,38400,8,1,0*3C\r\n"
29 
30 class AP_GPS_SIRF : public AP_GPS_Backend {
31 public:
33 
34  bool read();
35 
36  static bool _detect(struct SIRF_detect_state &state, uint8_t data);
37 
38  const char *name() const override { return "SIRF"; }
39 
40 private:
42  uint16_t fix_invalid;
43  uint16_t fix_type;
44  uint16_t week;
45  uint32_t time;
46  uint16_t year;
47  uint8_t month;
48  uint8_t day;
49  uint8_t hour;
50  uint8_t minute;
51  uint16_t second;
52  uint32_t satellites_used;
53  int32_t latitude;
54  int32_t longitude;
56  int32_t altitude_msl;
57  int8_t map_datum;
58  int16_t ground_speed;
59  int16_t ground_course;
60  int16_t res1;
61  int16_t climb_rate;
62  uint16_t heading_rate;
65  uint32_t time_error;
67  int32_t clock_bias;
68  uint32_t clock_bias_error;
69  int32_t clock_drift;
71  uint32_t distance;
72  uint16_t distance_error;
73  uint16_t heading_error;
74  uint8_t satellites;
75  uint8_t hdop;
76  uint8_t mode_info;
77  };
79  PREAMBLE1 = 0xa0,
80  PREAMBLE2 = 0xa2,
81  POSTAMBLE1 = 0xb0,
82  POSTAMBLE2 = 0xb3,
83  MSG_GEONAV = 0x29
84  };
86  FIX_3D = 0x6,
87  FIX_MASK = 0x7
88  };
89 
90 
91  // State machine state
92  uint8_t _step;
93  uint16_t _checksum;
94  bool _gather;
95  uint16_t _payload_length;
96  uint16_t _payload_counter;
97  uint8_t _msg_id;
98 
99  // Message buffer
100  union {
103  } _buffer;
104 
105  bool _parse_gps(void);
106  void _accumulate(uint8_t val);
107 
108  static const uint8_t _initialisation_blob[];
109 };
Definition: AP_GPS.h:48
uint16_t _payload_length
Definition: AP_GPS_SIRF.h:95
DEFINE_BYTE_ARRAY_METHODS sirf_geonav nav
Definition: AP_GPS_SIRF.h:102
int16_t horizontal_velocity_error
Definition: AP_GPS_SIRF.h:66
uint16_t _payload_counter
Definition: AP_GPS_SIRF.h:96
#define DEFINE_BYTE_ARRAY_METHODS
Definition: AP_Common.h:58
bool _gather
Definition: AP_GPS_SIRF.h:94
AP_GPS_SIRF(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port)
Definition: AP_GPS_SIRF.cpp:35
uint32_t vertical_position_error
Definition: AP_GPS_SIRF.h:64
bool _parse_gps(void)
uint8_t _msg_id
Definition: AP_GPS_SIRF.h:97
uint16_t _checksum
Definition: AP_GPS_SIRF.h:93
uint8_t _step
Definition: AP_GPS_SIRF.h:92
AP_GPS::GPS_State & state
public state for this instance
Definition: GPS_Backend.h:71
Common definitions and utility routines for the ArduPilot libraries.
union AP_GPS_SIRF::@35 _buffer
#define PACKED
Definition: AP_Common.h:28
uint32_t horizontal_position_error
Definition: AP_GPS_SIRF.h:63
static bool _detect(struct SIRF_detect_state &state, uint8_t data)
const char * name() const override
Definition: AP_GPS_SIRF.h:38
void _accumulate(uint8_t val)
static const uint8_t _initialisation_blob[]
Definition: AP_GPS_SIRF.h:108