Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_GPS/AP_GPS_GSOF.cpp
Views: 1798
/*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//19// Usage in SITL with hardware for debugging:20// sim_vehicle.py -v Plane -A "--serial3=uart:/dev/ttyUSB0" --console --map -DG21// param set GPS1_TYPE 11 // GSOF22// param set SERIAL3_PROTOCOL 5 // GPS23//24// Pure SITL usage:25// sim_vehicle.py -v Plane --console --map -DG26// param set SIM_GPS1_TYPE 11 // GSOF27// param set GPS1_TYPE 11 // GSOF28// param set SERIAL3_PROTOCOL 5 // GPS2930#define ALLOW_DOUBLE_MATH_FUNCTIONS3132#include "AP_GPS.h"33#include "AP_GPS_GSOF.h"34#include <AP_Logger/AP_Logger.h>35#include <AP_HAL/utility/sparse-endian.h>36#include <GCS_MAVLink/GCS.h>3738#if AP_GPS_GSOF_ENABLED3940extern const AP_HAL::HAL& hal;4142AP_GPS_GSOF::AP_GPS_GSOF(AP_GPS &_gps,43AP_GPS::Params &_params,44AP_GPS::GPS_State &_state,45AP_HAL::UARTDriver *_port) :46AP_GPS_Backend(_gps, _params, _state, _port)47{4849const uint16_t gsofmsgreq[5] = {50AP_GSOF::POS_TIME,51AP_GSOF::POS,52AP_GSOF::VEL,53AP_GSOF::DOP,54AP_GSOF::POS_SIGMA55};56// https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_Overview.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257COverview%257C_____057// The maximum number of outputs allowed with GSOF is 1058static_assert(ARRAY_SIZE(gsofmsgreq) <= 10, "The maximum number of outputs allowed with GSOF is 10.");59requested_msgs = AP_GSOF::MsgTypes(gsofmsgreq);606162constexpr uint8_t default_com_port = static_cast<uint8_t>(HW_Port::COM2);63params.com_port.set_default(default_com_port);64const auto com_port = params.com_port;65if (!validate_com_port(com_port)) {66// The user parameter for COM port is not a valid GSOF port67GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "GSOF instance %d has invalid COM port setting of %d", state.instance, (unsigned)com_port);68return;69}70requestBaud(static_cast<HW_Port>(unsigned(com_port)));7172const uint32_t now = AP_HAL::millis();73gsofmsg_time = now + 110;74}7576// Process all bytes available from the stream77//78bool79AP_GPS_GSOF::read(void)80{81const uint32_t now = AP_HAL::millis();8283if (gsofmsgreq_index < (requested_msgs.count())) {84const auto com_port = params.com_port.get();85if (!validate_com_port(com_port)) {86// The user parameter for COM port is not a valid GSOF port87return false;88}89if (now > gsofmsg_time) {90for (uint16_t i = next_req_gsof; i < requested_msgs.size(); i++){91if (requested_msgs.get(i)) {92next_req_gsof = i;93break;94}95}96requestGSOF(next_req_gsof, static_cast<HW_Port>(com_port), Output_Rate::FREQ_10_HZ);97gsofmsg_time = now + 110;98gsofmsgreq_index++;99next_req_gsof++;100}101}102103while (port->available() > 0) {104const uint8_t temp = port->read();105#if AP_GPS_DEBUG_LOGGING_ENABLED106log_data(&temp, 1);107#endif108AP_GSOF::MsgTypes parsed;109const int parse_status = parse(temp, parsed);110if(parse_status == PARSED_GSOF_DATA) {111if (parsed.get(AP_GSOF::POS_TIME) &&112parsed.get(AP_GSOF::POS) &&113parsed.get(AP_GSOF::VEL) &&114parsed.get(AP_GSOF::DOP) &&115parsed.get(AP_GSOF::POS_SIGMA)116)117{118pack_state_data();119return true;120}121}122}123124return false;125}126127void128AP_GPS_GSOF::requestBaud(const HW_Port portindex)129{130uint8_t buffer[19] = {0x02,0x00,0x64,0x0d,0x00,0x00,0x00, // application file record1310x03, 0x00, 0x01, 0x00, // file control information block1320x02, 0x04, static_cast<uint8_t>(portindex), 0x07, 0x00,0x00, // serial port baud format1330x00,0x03134}; // checksum135136buffer[4] = packetcount++;137138uint8_t checksum = 0;139for (uint8_t a = 1; a < (sizeof(buffer) - 1); a++) {140checksum += buffer[a];141}142143buffer[17] = checksum;144145port->write((const uint8_t*)buffer, sizeof(buffer));146}147148void149AP_GPS_GSOF::requestGSOF(const uint8_t messageType, const HW_Port portIndex, const Output_Rate rateHz)150{151uint8_t buffer[21] = {0x02,0x00,0x64,0x0f,0x00,0x00,0x00, // application file record1520x03,0x00,0x01,0x00, // file control information block1530x07,0x06,0x0a,static_cast<uint8_t>(portIndex),static_cast<uint8_t>(rateHz),0x00,messageType,0x00, // output message record1540x00,0x03155}; // checksum156157buffer[4] = packetcount++;158159uint8_t checksum = 0;160for (uint8_t a = 1; a < (sizeof(buffer) - 1); a++) {161checksum += buffer[a];162}163164buffer[19] = checksum;165166port->write((const uint8_t*)buffer, sizeof(buffer));167}168169bool170AP_GPS_GSOF::validate_com_port(const uint8_t com_port) const171{172switch(com_port) {173case static_cast<uint8_t>(HW_Port::COM1):174case static_cast<uint8_t>(HW_Port::COM2):175return true;176default:177return false;178}179}180181void182AP_GPS_GSOF::pack_state_data()183{184// TODO should we pack time data if there is no fix?185state.time_week_ms = pos_time.time_week_ms;186state.time_week = pos_time.time_week;187state.num_sats = pos_time.num_sats;188189if ((pos_time.pos_flags1 & 1)) { // New position190state.status = AP_GPS::GPS_OK_FIX_3D;191if ((pos_time.pos_flags2 & 1)) { // Differential position192state.status = AP_GPS::GPS_OK_FIX_3D_DGPS;193if (pos_time.pos_flags2 & 2) { // Differential position method194if (pos_time.pos_flags2 & 4) {// Differential position method195state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FIXED;196} else {197state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT;198}199}200}201} else {202state.status = AP_GPS::NO_FIX;203}204205state.location.lat = (int32_t)(RAD_TO_DEG_DOUBLE * position.latitude_rad * (double)1e7);206state.location.lng = (int32_t)(RAD_TO_DEG_DOUBLE * position.longitude_rad * (double)1e7);207state.location.alt = (int32_t)(position.altitude * 100);208state.last_gps_time_ms = AP_HAL::millis();209210if ((vel.velocity_flags & 1) == 1) {211state.ground_speed = vel.horizontal_velocity;212state.ground_course = wrap_360(degrees(vel.heading));213fill_3d_velocity();214state.velocity.z = -vel.vertical_velocity;215state.have_vertical_velocity = true;216}217218state.hdop = (uint16_t)(dop.hdop * 100);219state.vdop = (uint16_t)(dop.vdop * 100);220221state.horizontal_accuracy = (pos_sigma.sigma_east + pos_sigma.sigma_north) / 2;222state.vertical_accuracy = pos_sigma.sigma_up;223state.have_horizontal_accuracy = true;224state.have_vertical_accuracy = true;225}226#endif227228229