Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_GPS/AP_GPS_GSOF.h
9677 views
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
// https://receiverhelp.trimble.com/oem-gnss/index.html#Welcome.html?TocPath=_____1
20
21
#pragma once
22
23
#include "AP_GPS.h"
24
#include "GPS_Backend.h"
25
#include <AP_GSOF/AP_GSOF.h>
26
27
#if AP_GPS_GSOF_ENABLED
28
class AP_GPS_GSOF : public AP_GPS_Backend, public AP_GSOF
29
{
30
public:
31
AP_GPS_GSOF(AP_GPS &_gps, AP_GPS::Params &_params, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port);
32
33
AP_GPS::GPS_Status highest_supported_status(void) override WARN_IF_UNUSED {
34
return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED;
35
}
36
37
// Methods
38
bool read() override WARN_IF_UNUSED;
39
40
const char *name() const override { return "GSOF"; }
41
42
private:
43
44
// Configure the GPS device
45
bool configure();
46
47
// A subset of the port identifiers in the GSOF protocol that are used for serial.
48
// Ethernet, USB, etc are not supported by the GPS driver at this time so they are omitted.
49
// These values are not documented in the API.
50
enum class HW_Port {
51
COM1 = 0, // RS232 serial
52
COM2 = 1, // TTL serial
53
};
54
55
// A subset of the data frequencies in the GSOF protocol that are used for serial.
56
// These values are not documented in the API.
57
enum class Output_Rate {
58
FREQ_10_HZ = 1,
59
FREQ_50_HZ = 15,
60
FREQ_100_HZ = 16,
61
};
62
63
// Send a request to the GPS to set the baud rate on the specified port.
64
// Note - these request functions currently ignore the ACK from the device.
65
// If the device is already sending serial traffic, there is no mechanism to prevent conflict.
66
// According to the manufacturer, the best approach is to switch to ethernet.
67
void requestBaud(const HW_Port portIndex);
68
// Send a request to the GPS to enable a message type on the port at the specified rate.
69
void requestGSOF(const uint8_t messageType, const HW_Port portIndex, const Output_Rate rateHz);
70
71
bool validate_baud(const uint8_t baud) const WARN_IF_UNUSED;
72
bool validate_com_port(const uint8_t com_port) const WARN_IF_UNUSED;
73
74
void pack_state_data();
75
76
uint8_t packetcount;
77
uint32_t gsofmsg_time;
78
uint8_t gsofmsgreq_index;
79
uint16_t next_req_gsof;
80
AP_GSOF::MsgTypes requested_msgs;
81
};
82
#endif
83
84