/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/1415//16// Trimble GPS driver for ArduPilot.17// Code by Michael Oborne18// https://receiverhelp.trimble.com/oem-gnss/index.html#Welcome.html?TocPath=_____11920#pragma once2122#include "AP_GPS.h"23#include "GPS_Backend.h"24#include <AP_GSOF/AP_GSOF.h>2526#if AP_GPS_GSOF_ENABLED27class AP_GPS_GSOF : public AP_GPS_Backend, public AP_GSOF28{29public:30AP_GPS_GSOF(AP_GPS &_gps, AP_GPS::Params &_params, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port);3132AP_GPS::GPS_Status highest_supported_status(void) override WARN_IF_UNUSED {33return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED;34}3536// Methods37bool read() override WARN_IF_UNUSED;3839const char *name() const override { return "GSOF"; }4041private:4243// Configure the GPS device44bool configure();4546// A subset of the port identifiers in the GSOF protocol that are used for serial.47// Ethernet, USB, etc are not supported by the GPS driver at this time so they are omitted.48// These values are not documented in the API.49enum class HW_Port {50COM1 = 0, // RS232 serial51COM2 = 1, // TTL serial52};5354// A subset of the data frequencies in the GSOF protocol that are used for serial.55// These values are not documented in the API.56enum class Output_Rate {57FREQ_10_HZ = 1,58FREQ_50_HZ = 15,59FREQ_100_HZ = 16,60};6162// Send a request to the GPS to set the baud rate on the specified port.63// Note - these request functions currently ignore the ACK from the device.64// If the device is already sending serial traffic, there is no mechanism to prevent conflict.65// According to the manufacturer, the best approach is to switch to ethernet.66void requestBaud(const HW_Port portIndex);67// Send a request to the GPS to enable a message type on the port at the specified rate.68void requestGSOF(const uint8_t messageType, const HW_Port portIndex, const Output_Rate rateHz);6970bool validate_baud(const uint8_t baud) const WARN_IF_UNUSED;71bool validate_com_port(const uint8_t com_port) const WARN_IF_UNUSED;7273void pack_state_data();7475uint8_t packetcount;76uint32_t gsofmsg_time;77uint8_t gsofmsgreq_index;78uint16_t next_req_gsof;79AP_GSOF::MsgTypes requested_msgs;80};81#endif828384