APM:Libraries
AP_GPS_ERB.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 // Emlid Reach Binary (ERB) GPS driver for ArduPilot.
18 // ERB protocol: http://files.emlid.com/ERB.pdf
19 
20 #pragma once
21 
22 #include <AP_HAL/AP_HAL.h>
23 
24 #include "AP_GPS.h"
25 #include "GPS_Backend.h"
26 
27 class AP_GPS_ERB : public AP_GPS_Backend
28 {
29 public:
30  AP_GPS_ERB(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port);
31 
32  // Methods
33  bool read();
34 
36 
37  bool supports_mavlink_gps_rtk_message() { return true; }
38 
39  static bool _detect(struct ERB_detect_state &state, uint8_t data);
40 
41  const char *name() const override { return "ERB"; }
42 
43 private:
44  struct PACKED erb_header {
45  uint8_t preamble1;
46  uint8_t preamble2;
47  uint8_t msg_id;
48  uint16_t length;
49  };
50  struct PACKED erb_ver {
51  uint32_t time;
52  uint8_t ver_high;
53  uint8_t ver_medium;
54  uint8_t ver_low;
55  };
56  struct PACKED erb_pos {
57  uint32_t time;
58  double longitude;
59  double latitude;
61  double altitude_msl;
63  uint32_t vertical_accuracy;
64  };
65  struct PACKED erb_stat {
66  uint32_t time;
67  uint16_t week;
68  uint8_t fix_type;
69  uint8_t fix_status;
70  uint8_t satellites;
71  };
72  struct PACKED erb_dops {
73  uint32_t time;
74  uint16_t gDOP;
75  uint16_t pDOP;
76  uint16_t vDOP;
77  uint16_t hDOP;
78  };
79  struct PACKED erb_vel {
80  uint32_t time;
81  int32_t vel_north;
82  int32_t vel_east;
83  int32_t vel_down;
84  uint32_t speed_2d;
85  int32_t heading_2d;
86  uint32_t speed_accuracy;
87  };
88  struct PACKED erb_rtk {
89  uint8_t base_num_sats;
90  uint16_t age_cs;
91  int32_t baseline_N_mm;
92  int32_t baseline_E_mm;
93  int32_t baseline_D_mm;
94  uint16_t ar_ratio;
95  uint16_t base_week_number;
96  uint32_t base_time_week_ms;
97  };
98 
99  // Receive buffer
100  union PACKED {
108  } _buffer;
109 
111  PREAMBLE1 = 0x45,
112  PREAMBLE2 = 0x52,
113  MSG_VER = 0x01,
114  MSG_POS = 0x02,
115  MSG_STAT = 0x03,
116  MSG_DOPS = 0x04,
117  MSG_VEL = 0x05,
118  MSG_RTK = 0x07,
119  };
120 
122  FIX_NONE = 0x00,
123  FIX_SINGLE = 0x01,
124  FIX_FLOAT = 0x02,
125  FIX_FIX = 0x03,
126  };
127 
128  // Packet checksum accumulators
129  uint8_t _ck_a;
130  uint8_t _ck_b;
131 
132  // State machine state
133  uint8_t _step;
134  uint8_t _msg_id;
135  uint16_t _payload_length;
137 
138  // 8 bit count of fix messages processed, used for periodic processing
139  uint8_t _fix_count;
140 
141  uint32_t _last_pos_time;
142  uint32_t _last_vel_time;
143 
144  // do we have new position information?
146  // do we have new speed information?
147  bool _new_speed:1;
148 
149  // Buffer parse & GPS state update
150  bool _parse_gps();
151 
152  // used to update fix between status and position packets
154 };
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
uint32_t time
GPS time of week of the navigation epoch [ms].
Definition: AP_GPS_ERB.h:51
Definition: AP_GPS.h:48
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
bool supports_mavlink_gps_rtk_message()
Definition: AP_GPS_ERB.h:37
uint8_t _step
Definition: AP_GPS_ERB.h:133
bool _new_speed
Definition: AP_GPS_ERB.h:147
#define DEFINE_BYTE_ARRAY_METHODS
Definition: AP_Common.h:58
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
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
uint32_t time
GPS time of week of the navigation epoch [ms].
Definition: AP_GPS_ERB.h:73
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
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
uint8_t _ck_a
Definition: AP_GPS_ERB.h:129
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
double altitude_ellipsoid
Height above ellipsoid [m].
Definition: AP_GPS_ERB.h:60
GPS_Status
GPS status codes.
Definition: AP_GPS.h:96
uint16_t _payload_counter
Definition: AP_GPS_ERB.h:136
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
AP_GPS::GPS_Status next_fix
Definition: AP_GPS_ERB.h:153
union AP_GPS_ERB::PACKED _buffer
AP_GPS::GPS_State & state
public state for this instance
Definition: GPS_Backend.h:71
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
uint16_t pDOP
Position DOP.
Definition: AP_GPS_ERB.h:75
uint16_t hDOP
Horizontal DOP.
Definition: AP_GPS_ERB.h:77
AP_GPS::GPS_Status highest_supported_status(void)
Definition: AP_GPS_ERB.h:35
AP_GPS_ERB(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port)
Definition: AP_GPS_ERB.cpp:35
uint16_t gDOP
Geometric DOP.
Definition: AP_GPS_ERB.h:74
int32_t baseline_E_mm
distance between base and rover along the east axis in millimeters
Definition: AP_GPS_ERB.h:92
uint32_t base_time_week_ms
GPS Time of Week of last baseline in milliseconds.
Definition: AP_GPS_ERB.h:96
uint8_t _msg_id
Definition: AP_GPS_ERB.h:134
uint16_t age_cs
Age of the corrections in centiseconds (0 when no corrections, 0xFFFF indicates overflow) ...
Definition: AP_GPS_ERB.h:90
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
const char * name() const override
Definition: AP_GPS_ERB.h:41