CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_GPS/AP_GPS_GSOF.cpp
Views: 1798
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
// Usage in SITL with hardware for debugging:
21
// sim_vehicle.py -v Plane -A "--serial3=uart:/dev/ttyUSB0" --console --map -DG
22
// param set GPS1_TYPE 11 // GSOF
23
// param set SERIAL3_PROTOCOL 5 // GPS
24
//
25
// Pure SITL usage:
26
// sim_vehicle.py -v Plane --console --map -DG
27
// param set SIM_GPS1_TYPE 11 // GSOF
28
// param set GPS1_TYPE 11 // GSOF
29
// param set SERIAL3_PROTOCOL 5 // GPS
30
31
#define ALLOW_DOUBLE_MATH_FUNCTIONS
32
33
#include "AP_GPS.h"
34
#include "AP_GPS_GSOF.h"
35
#include <AP_Logger/AP_Logger.h>
36
#include <AP_HAL/utility/sparse-endian.h>
37
#include <GCS_MAVLink/GCS.h>
38
39
#if AP_GPS_GSOF_ENABLED
40
41
extern const AP_HAL::HAL& hal;
42
43
AP_GPS_GSOF::AP_GPS_GSOF(AP_GPS &_gps,
44
AP_GPS::Params &_params,
45
AP_GPS::GPS_State &_state,
46
AP_HAL::UARTDriver *_port) :
47
AP_GPS_Backend(_gps, _params, _state, _port)
48
{
49
50
const uint16_t gsofmsgreq[5] = {
51
AP_GSOF::POS_TIME,
52
AP_GSOF::POS,
53
AP_GSOF::VEL,
54
AP_GSOF::DOP,
55
AP_GSOF::POS_SIGMA
56
};
57
// https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_Overview.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257COverview%257C_____0
58
// The maximum number of outputs allowed with GSOF is 10
59
static_assert(ARRAY_SIZE(gsofmsgreq) <= 10, "The maximum number of outputs allowed with GSOF is 10.");
60
requested_msgs = AP_GSOF::MsgTypes(gsofmsgreq);
61
62
63
constexpr uint8_t default_com_port = static_cast<uint8_t>(HW_Port::COM2);
64
params.com_port.set_default(default_com_port);
65
const auto com_port = params.com_port;
66
if (!validate_com_port(com_port)) {
67
// The user parameter for COM port is not a valid GSOF port
68
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "GSOF instance %d has invalid COM port setting of %d", state.instance, (unsigned)com_port);
69
return;
70
}
71
requestBaud(static_cast<HW_Port>(unsigned(com_port)));
72
73
const uint32_t now = AP_HAL::millis();
74
gsofmsg_time = now + 110;
75
}
76
77
// Process all bytes available from the stream
78
//
79
bool
80
AP_GPS_GSOF::read(void)
81
{
82
const uint32_t now = AP_HAL::millis();
83
84
if (gsofmsgreq_index < (requested_msgs.count())) {
85
const auto com_port = params.com_port.get();
86
if (!validate_com_port(com_port)) {
87
// The user parameter for COM port is not a valid GSOF port
88
return false;
89
}
90
if (now > gsofmsg_time) {
91
for (uint16_t i = next_req_gsof; i < requested_msgs.size(); i++){
92
if (requested_msgs.get(i)) {
93
next_req_gsof = i;
94
break;
95
}
96
}
97
requestGSOF(next_req_gsof, static_cast<HW_Port>(com_port), Output_Rate::FREQ_10_HZ);
98
gsofmsg_time = now + 110;
99
gsofmsgreq_index++;
100
next_req_gsof++;
101
}
102
}
103
104
while (port->available() > 0) {
105
const uint8_t temp = port->read();
106
#if AP_GPS_DEBUG_LOGGING_ENABLED
107
log_data(&temp, 1);
108
#endif
109
AP_GSOF::MsgTypes parsed;
110
const int parse_status = parse(temp, parsed);
111
if(parse_status == PARSED_GSOF_DATA) {
112
if (parsed.get(AP_GSOF::POS_TIME) &&
113
parsed.get(AP_GSOF::POS) &&
114
parsed.get(AP_GSOF::VEL) &&
115
parsed.get(AP_GSOF::DOP) &&
116
parsed.get(AP_GSOF::POS_SIGMA)
117
)
118
{
119
pack_state_data();
120
return true;
121
}
122
}
123
}
124
125
return false;
126
}
127
128
void
129
AP_GPS_GSOF::requestBaud(const HW_Port portindex)
130
{
131
uint8_t buffer[19] = {0x02,0x00,0x64,0x0d,0x00,0x00,0x00, // application file record
132
0x03, 0x00, 0x01, 0x00, // file control information block
133
0x02, 0x04, static_cast<uint8_t>(portindex), 0x07, 0x00,0x00, // serial port baud format
134
0x00,0x03
135
}; // checksum
136
137
buffer[4] = packetcount++;
138
139
uint8_t checksum = 0;
140
for (uint8_t a = 1; a < (sizeof(buffer) - 1); a++) {
141
checksum += buffer[a];
142
}
143
144
buffer[17] = checksum;
145
146
port->write((const uint8_t*)buffer, sizeof(buffer));
147
}
148
149
void
150
AP_GPS_GSOF::requestGSOF(const uint8_t messageType, const HW_Port portIndex, const Output_Rate rateHz)
151
{
152
uint8_t buffer[21] = {0x02,0x00,0x64,0x0f,0x00,0x00,0x00, // application file record
153
0x03,0x00,0x01,0x00, // file control information block
154
0x07,0x06,0x0a,static_cast<uint8_t>(portIndex),static_cast<uint8_t>(rateHz),0x00,messageType,0x00, // output message record
155
0x00,0x03
156
}; // checksum
157
158
buffer[4] = packetcount++;
159
160
uint8_t checksum = 0;
161
for (uint8_t a = 1; a < (sizeof(buffer) - 1); a++) {
162
checksum += buffer[a];
163
}
164
165
buffer[19] = checksum;
166
167
port->write((const uint8_t*)buffer, sizeof(buffer));
168
}
169
170
bool
171
AP_GPS_GSOF::validate_com_port(const uint8_t com_port) const
172
{
173
switch(com_port) {
174
case static_cast<uint8_t>(HW_Port::COM1):
175
case static_cast<uint8_t>(HW_Port::COM2):
176
return true;
177
default:
178
return false;
179
}
180
}
181
182
void
183
AP_GPS_GSOF::pack_state_data()
184
{
185
// TODO should we pack time data if there is no fix?
186
state.time_week_ms = pos_time.time_week_ms;
187
state.time_week = pos_time.time_week;
188
state.num_sats = pos_time.num_sats;
189
190
if ((pos_time.pos_flags1 & 1)) { // New position
191
state.status = AP_GPS::GPS_OK_FIX_3D;
192
if ((pos_time.pos_flags2 & 1)) { // Differential position
193
state.status = AP_GPS::GPS_OK_FIX_3D_DGPS;
194
if (pos_time.pos_flags2 & 2) { // Differential position method
195
if (pos_time.pos_flags2 & 4) {// Differential position method
196
state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FIXED;
197
} else {
198
state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT;
199
}
200
}
201
}
202
} else {
203
state.status = AP_GPS::NO_FIX;
204
}
205
206
state.location.lat = (int32_t)(RAD_TO_DEG_DOUBLE * position.latitude_rad * (double)1e7);
207
state.location.lng = (int32_t)(RAD_TO_DEG_DOUBLE * position.longitude_rad * (double)1e7);
208
state.location.alt = (int32_t)(position.altitude * 100);
209
state.last_gps_time_ms = AP_HAL::millis();
210
211
if ((vel.velocity_flags & 1) == 1) {
212
state.ground_speed = vel.horizontal_velocity;
213
state.ground_course = wrap_360(degrees(vel.heading));
214
fill_3d_velocity();
215
state.velocity.z = -vel.vertical_velocity;
216
state.have_vertical_velocity = true;
217
}
218
219
state.hdop = (uint16_t)(dop.hdop * 100);
220
state.vdop = (uint16_t)(dop.vdop * 100);
221
222
state.horizontal_accuracy = (pos_sigma.sigma_east + pos_sigma.sigma_north) / 2;
223
state.vertical_accuracy = pos_sigma.sigma_up;
224
state.have_horizontal_accuracy = true;
225
state.have_vertical_accuracy = true;
226
}
227
#endif
228
229