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_SBF.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// Septentrio GPS driver for ArduPilot.17// Code by Michael Oborne18//1920#include "AP_GPS.h"21#include "AP_GPS_SBF.h"22#include <GCS_MAVLink/GCS.h>23#include <AP_InternalError/AP_InternalError.h>24#include <stdio.h>25#include <ctype.h>2627#if AP_GPS_SBF_ENABLED28extern const AP_HAL::HAL& hal;2930#define SBF_DEBUGGING 03132#if SBF_DEBUGGING33# define Debug(fmt, args ...) \34do { \35hal.console->printf("%s:%d: " fmt "\n", \36__FUNCTION__, __LINE__, \37## args); \38hal.scheduler->delay(1); \39} while(0)40#else41# define Debug(fmt, args ...)42#endif4344#ifndef GPS_SBF_STREAM_NUMBER45#define GPS_SBF_STREAM_NUMBER 146#endif4748#define SBF_EXCESS_COMMAND_BYTES 5 // 2 start bytes + validity byte + space byte + endline byte4950#define RX_ERROR_MASK (CONGESTION | \51MISSEDEVENT | \52CPUOVERLOAD | \53INVALIDCONFIG | \54OUTOFGEOFENCE)5556constexpr const char *AP_GPS_SBF::portIdentifiers[];57constexpr const char* AP_GPS_SBF::_initialisation_blob[];58constexpr const char* AP_GPS_SBF::sbas_on_blob[];5960AP_GPS_SBF::AP_GPS_SBF(AP_GPS &_gps,61AP_GPS::Params &_params,62AP_GPS::GPS_State &_state,63AP_HAL::UARTDriver *_port) :64AP_GPS_Backend(_gps, _params, _state, _port)65{66sbf_msg.sbf_state = sbf_msg_parser_t::PREAMBLE1;6768_config_last_ack_time = AP_HAL::millis();6970// if we ever parse RTK observations it will always be of type NED, so set it once71state.rtk_baseline_coords_type = RTK_BASELINE_COORDINATE_SYSTEM_NED;7273// yaw available when option bit set or using dual antenna74if (option_set(AP_GPS::DriverOptions::SBF_UseBaseForYaw) ||75(get_type() == AP_GPS::GPS_Type::GPS_TYPE_SBF_DUAL_ANTENNA)) {76state.gps_yaw_configured = true;77}78}7980AP_GPS_SBF::~AP_GPS_SBF (void) {81free(config_string);82}8384// Process all bytes available from the stream85//86bool87AP_GPS_SBF::read(void)88{89bool ret = false;90uint32_t available_bytes = port->available();91for (uint32_t i = 0; i < available_bytes; i++) {92uint8_t temp = port->read();93#if AP_GPS_DEBUG_LOGGING_ENABLED94log_data(&temp, 1);95#endif96ret |= parse(temp);97}9899const uint32_t now = AP_HAL::millis();100if (gps._auto_config != AP_GPS::GPS_AUTO_CONFIG_DISABLE) {101if (config_step != Config_State::Complete) {102if (now > _init_blob_time) {103if (now > _config_last_ack_time + 2000) {104const size_t port_enable_len = strlen(_port_enable);105if (port_enable_len <= port->txspace()) {106// try to enable input on the GPS port if we have not made progress on configuring it107Debug("SBF Sending port enable");108port->write((const uint8_t*)_port_enable, port_enable_len);109_config_last_ack_time = now;110}111} else if (readyForCommand) {112if (config_string == nullptr) {113switch (config_step) {114case Config_State::Baud_Rate:115if (asprintf(&config_string, "scs,COM%d,baud%d,bits8,No,bit1,%s\n",116(int)params.com_port,117230400,118port->get_flow_control() != AP_HAL::UARTDriver::flow_control::FLOW_CONTROL_ENABLE ? "none" : "RTS|CTS") == -1) {119config_string = nullptr;120}121break;122case Config_State::SSO:123const char *extra_config;124switch (get_type()) {125case AP_GPS::GPS_Type::GPS_TYPE_SBF_DUAL_ANTENNA:126extra_config = "+AttCovEuler+AuxAntPositions";127break;128case AP_GPS::GPS_Type::GPS_TYPE_SBF:129default:130extra_config = "";131break;132}133if (asprintf(&config_string, "sso,Stream%d,COM%d,PVTGeodetic+DOP+ReceiverStatus+VelCovGeodetic+BaseVectorGeod%s,msec100\n",134(int)GPS_SBF_STREAM_NUMBER,135(int)params.com_port,136extra_config) == -1) {137config_string = nullptr;138}139break;140case Config_State::Constellation:141if ((params.gnss_mode&0x6F)!=0) {142//IMES not taken into account by Septentrio receivers143if (asprintf(&config_string, "sst, %s%s%s%s%s%s\n", (params.gnss_mode&(1U<<0))!=0 ? "GPS" : "",144(params.gnss_mode&(1U<<1))!=0 ? ((params.gnss_mode&0x01)==0 ? "SBAS" : "+SBAS") : "",145(params.gnss_mode&(1U<<2))!=0 ? ((params.gnss_mode&0x03)==0 ? "GALILEO" : "+GALILEO") : "",146(params.gnss_mode&(1U<<3))!=0 ? ((params.gnss_mode&0x07)==0 ? "BEIDOU" : "+BEIDOU") : "",147(params.gnss_mode&(1U<<5))!=0 ? ((params.gnss_mode&0x0F)==0 ? "QZSS" : "+QZSS") : "",148(params.gnss_mode&(1U<<6))!=0 ? ((params.gnss_mode&0x2F)==0 ? "GLONASS" : "+GLONASS") : "") == -1) {149config_string=nullptr;150}151}152break;153case Config_State::Blob:154if (asprintf(&config_string, "%s\n", _initialisation_blob[_init_blob_index]) == -1) {155config_string = nullptr;156}157break;158case Config_State::SBAS:159switch ((AP_GPS::SBAS_Mode)gps._sbas_mode) {160case AP_GPS::SBAS_Mode::Disabled:161if (asprintf(&config_string, "%s\n", sbas_off) == -1) {162config_string = nullptr;163}164break;165case AP_GPS::SBAS_Mode::Enabled:166if (asprintf(&config_string, "%s\n", sbas_on_blob[_init_blob_index]) == -1) {167config_string = nullptr;168}169break;170case AP_GPS::SBAS_Mode::DoNotChange:171config_string = nullptr;172config_step = Config_State::Complete;173break;174}175break;176case Config_State::SGA:177{178const char *targetGA = "none";179if (get_type() == AP_GPS::GPS_Type::GPS_TYPE_SBF_DUAL_ANTENNA) {180targetGA = "MultiAntenna";181}182if (asprintf(&config_string, "sga, %s\n", targetGA)) {183config_string = nullptr;184}185break;186}187case Config_State::Complete:188// should never reach here, why search for a config if we have fully configured already189INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);190break;191}192}193194if (config_string != nullptr) {195const size_t config_length = strlen(config_string);196if (config_length <= port->txspace()) {197Debug("SBF sending init string: %s", config_string);198port->write((const uint8_t*)config_string, config_length);199readyForCommand = false;200}201}202}203}204} else if (gps._raw_data == 2) { // only manage disarm/rearms when the user opts into it205if (hal.util->get_soft_armed()) {206_has_been_armed = true;207} else if (_has_been_armed && (RxState & SBF_DISK_MOUNTED)) {208// since init is done at this point and unmounting should be rate limited,209// take over the _init_blob_time variable210if (now > _init_blob_time) {211unmount_disk();212_init_blob_time = now + 1000;213}214}215}216}217218// yaw timeout after 300 milliseconds219if ((now - state.gps_yaw_time_ms) > 300) {220state.have_gps_yaw = false;221state.have_gps_yaw_accuracy = false;222}223224return ret;225}226227bool AP_GPS_SBF::logging_healthy(void) const228{229switch (gps._raw_data) {230case 1:231default:232return (RxState & SBF_DISK_MOUNTED) && (RxState & SBF_DISK_ACTIVITY);233case 2:234return ((RxState & SBF_DISK_MOUNTED) && (RxState & SBF_DISK_ACTIVITY)) || (!hal.util->get_soft_armed() && _has_been_armed);235}236}237238bool239AP_GPS_SBF::parse(uint8_t temp)240{241switch (sbf_msg.sbf_state)242{243default:244case sbf_msg_parser_t::PREAMBLE1:245if (temp == SBF_PREAMBLE1) {246sbf_msg.sbf_state = sbf_msg_parser_t::PREAMBLE2;247sbf_msg.read = 0;248} else {249// attempt to detect command prompt250portIdentifier[portLength++] = (char)temp;251bool foundPossiblePort = false;252for (const char *portId : portIdentifiers) {253if (strncmp(portId, portIdentifier, MIN(portLength, 3)) == 0) {254// we found one of the COM/USB/IP related ports255if (portLength == 4) {256// validate that we have an ascii number257if (isdigit((char)temp)) {258foundPossiblePort = true;259break;260}261} else if (portLength >= sizeof(portIdentifier)) {262if ((char)temp == '>') {263readyForCommand = true;264Debug("SBF: Ready for command");265}266} else {267foundPossiblePort = true;268}269break;270}271}272if (!foundPossiblePort) {273portLength = 0;274}275}276break;277case sbf_msg_parser_t::PREAMBLE2:278if (temp == SBF_PREAMBLE2) {279sbf_msg.sbf_state = sbf_msg_parser_t::CRC1;280} else if (temp == 'R') {281Debug("SBF got a response\n");282sbf_msg.sbf_state = sbf_msg_parser_t::COMMAND_LINE;283}284else285{286sbf_msg.sbf_state = sbf_msg_parser_t::PREAMBLE1;287}288break;289case sbf_msg_parser_t::CRC1:290sbf_msg.crc = temp;291sbf_msg.sbf_state = sbf_msg_parser_t::CRC2;292break;293case sbf_msg_parser_t::CRC2:294sbf_msg.crc += (uint16_t)(temp << 8);295sbf_msg.sbf_state = sbf_msg_parser_t::BLOCKID1;296break;297case sbf_msg_parser_t::BLOCKID1:298sbf_msg.blockid = temp;299sbf_msg.sbf_state = sbf_msg_parser_t::BLOCKID2;300break;301case sbf_msg_parser_t::BLOCKID2:302sbf_msg.blockid += (uint16_t)(temp << 8);303sbf_msg.sbf_state = sbf_msg_parser_t::LENGTH1;304break;305case sbf_msg_parser_t::LENGTH1:306sbf_msg.length = temp;307sbf_msg.sbf_state = sbf_msg_parser_t::LENGTH2;308break;309case sbf_msg_parser_t::LENGTH2:310sbf_msg.length += (uint16_t)(temp << 8);311sbf_msg.sbf_state = sbf_msg_parser_t::DATA;312if (sbf_msg.length % 4 != 0) {313sbf_msg.sbf_state = sbf_msg_parser_t::PREAMBLE1;314Debug("bad packet length=%u\n", (unsigned)sbf_msg.length);315}316if (sbf_msg.length < 8) {317Debug("bad packet length=%u\n", (unsigned)sbf_msg.length);318sbf_msg.sbf_state = sbf_msg_parser_t::PREAMBLE1;319crc_error_counter++; // this is a probable buffer overflow, but this320// indicates not enough bytes to do a crc321break;322}323break;324case sbf_msg_parser_t::DATA:325if (sbf_msg.read < sizeof(sbf_msg.data)) {326sbf_msg.data.bytes[sbf_msg.read] = temp;327}328sbf_msg.read++;329if (sbf_msg.read >= (sbf_msg.length - 8)) {330if (sbf_msg.read > sizeof(sbf_msg.data)) {331// not interested in these large messages332sbf_msg.sbf_state = sbf_msg_parser_t::PREAMBLE1;333break;334}335uint16_t crc = crc16_ccitt((uint8_t*)&sbf_msg.blockid, 2, 0);336crc = crc16_ccitt((uint8_t*)&sbf_msg.length, 2, crc);337crc = crc16_ccitt((uint8_t*)&sbf_msg.data, sbf_msg.length - 8, crc);338339sbf_msg.sbf_state = sbf_msg_parser_t::PREAMBLE1;340341if (sbf_msg.crc == crc) {342return process_message();343} else {344Debug("crc fail\n");345crc_error_counter++;346}347}348break;349case sbf_msg_parser_t::COMMAND_LINE:350if (sbf_msg.read < (sizeof(sbf_msg.data) - 1)) {351sbf_msg.data.bytes[sbf_msg.read] = temp;352} else {353// we don't have enough buffer to compare the commands354// most probable cause is that a user injected a longer command then355// we have buffer for, or it could be a corruption, either way we356// simply ignore the result357sbf_msg.sbf_state = sbf_msg_parser_t::PREAMBLE1;358break;359}360sbf_msg.read++;361if (temp == '\n') {362sbf_msg.data.bytes[sbf_msg.read] = 0;363364// received the result, lets assess it365if (sbf_msg.data.bytes[0] == ':') {366// valid command, determine if it was the one we were trying367// to send in the configuration sequence368if (config_string != nullptr) {369if (!strncmp(config_string, (char *)(sbf_msg.data.bytes + 2),370sbf_msg.read - SBF_EXCESS_COMMAND_BYTES)) {371Debug("SBF Ack Command: %s\n", sbf_msg.data.bytes);372free(config_string);373config_string = nullptr;374switch (config_step) {375case Config_State::Baud_Rate:376config_step = Config_State::SSO;377break;378case Config_State::SSO:379config_step = Config_State::Constellation;380break;381case Config_State::Constellation:382config_step = Config_State::Blob;383break;384case Config_State::Blob:385_init_blob_index++;386if (_init_blob_index >= ARRAY_SIZE(_initialisation_blob)) {387config_step = Config_State::SBAS;388_init_blob_index = 0;389}390break;391case Config_State::SBAS:392_init_blob_index++;393if ((gps._sbas_mode == AP_GPS::SBAS_Mode::Disabled)394||_init_blob_index >= ARRAY_SIZE(sbas_on_blob)) {395config_step = Config_State::SGA;396}397break;398case Config_State::SGA:399config_step = Config_State::Complete;400break;401case Config_State::Complete:402// should never reach here, this implies that we validated a config string when we hadn't sent any403INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);404break;405}406_config_last_ack_time = AP_HAL::millis();407} else {408Debug("SBF Ack command (unexpected): %s\n", sbf_msg.data.bytes);409}410}411} else {412// rejected command, send it out as a debug413Debug("SBF NACK Command: %s\n", sbf_msg.data.bytes);414}415// resume normal parsing416sbf_msg.sbf_state = sbf_msg_parser_t::PREAMBLE1;417break;418}419break;420}421422return false;423}424425static bool is_DNU(double value)426{427constexpr double DNU = -2e-10f;428#pragma GCC diagnostic push429#pragma GCC diagnostic ignored "-Wfloat-equal" // suppress -Wfloat-equal as it's false positive when testing for DNU values430return value != DNU;431#pragma GCC diagnostic pop432}433434bool435AP_GPS_SBF::process_message(void)436{437uint16_t blockid = (sbf_msg.blockid & 8191u);438439Debug("BlockID %d", blockid);440441switch (blockid) {442case PVTGeodetic:443{444const msg4007 &temp = sbf_msg.data.msg4007u;445446// Update time state447if (temp.WNc != 65535) {448state.time_week = temp.WNc;449state.time_week_ms = (uint32_t)(temp.TOW);450}451452check_new_itow(temp.TOW, sbf_msg.length);453state.last_gps_time_ms = AP_HAL::millis();454455// Update velocity state (don't use −2·10^10)456if (temp.Vn > -200000) {457state.velocity.x = (float)(temp.Vn);458state.velocity.y = (float)(temp.Ve);459state.velocity.z = (float)(-temp.Vu);460461state.have_vertical_velocity = true;462463velocity_to_speed_course(state);464state.rtk_age_ms = temp.MeanCorrAge * 10;465466// value is expressed as twice the rms error = int16 * 0.01/2467state.horizontal_accuracy = (float)temp.HAccuracy * 0.005f;468state.vertical_accuracy = (float)temp.VAccuracy * 0.005f;469state.have_horizontal_accuracy = true;470state.have_vertical_accuracy = true;471}472473// Update position state (don't use -2·10^10)474if (temp.Latitude > -200000) {475state.location.lat = (int32_t)(temp.Latitude * RAD_TO_DEG_DOUBLE * (double)1e7);476state.location.lng = (int32_t)(temp.Longitude * RAD_TO_DEG_DOUBLE * (double)1e7);477state.have_undulation = !is_DNU(temp.Undulation);478double height = temp.Height; // in metres479if (state.have_undulation) {480height -= temp.Undulation;481state.undulation = -temp.Undulation;482}483set_alt_amsl_cm(state, (float)height * 1e2f); // m -> cm484}485486state.num_sats = temp.NrSV;487if (temp.NrSV == 255) {488// Do-Not-Use value for NrSV field in PVTGeodetic message489state.num_sats = 0;490}491492Debug("temp.Mode=0x%02x\n", (unsigned)temp.Mode);493switch (temp.Mode & 15) {494case 0: // no pvt495state.status = AP_GPS::NO_FIX;496break;497case 1: // standalone498state.status = AP_GPS::GPS_OK_FIX_3D;499break;500case 2: // dgps501state.status = AP_GPS::GPS_OK_FIX_3D_DGPS;502break;503case 3: // fixed location504state.status = AP_GPS::GPS_OK_FIX_3D;505break;506case 4: // rtk fixed507state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FIXED;508break;509case 5: // rtk float510state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT;511break;512case 6: // sbas513state.status = AP_GPS::GPS_OK_FIX_3D_DGPS;514break;515case 7: // moving rtk fixed516state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FIXED;517break;518case 8: // moving rtk float519state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT;520break;521}522523if ((temp.Mode & 64) > 0) { // gps is in base mode524state.status = AP_GPS::NO_FIX;525} else if ((temp.Mode & 128) > 0) { // gps only has 2d fix526state.status = AP_GPS::GPS_OK_FIX_2D;527}528529return true;530}531case DOP:532{533const msg4001 &temp = sbf_msg.data.msg4001u;534check_new_itow(temp.TOW, sbf_msg.length);535536state.hdop = temp.HDOP;537state.vdop = temp.VDOP;538break;539}540case ReceiverStatus:541{542const msg4014 &temp = sbf_msg.data.msg4014u;543check_new_itow(temp.TOW, sbf_msg.length);544RxState = temp.RxState;545if ((RxError & RX_ERROR_MASK) != (temp.RxError & RX_ERROR_MASK)) {546GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GPS %u: SBF error changed (0x%08x/0x%08x)", (unsigned int)(state.instance + 1),547(unsigned int)(RxError & RX_ERROR_MASK), (unsigned int)(temp.RxError & RX_ERROR_MASK));548}549RxError = temp.RxError;550break;551}552case VelCovGeodetic:553{554const msg5908 &temp = sbf_msg.data.msg5908u;555556check_new_itow(temp.TOW, sbf_msg.length);557// select the maximum variance, as the EKF will apply it to all the columns in it's estimate558// FIXME: Support returning the covariance matrix to the EKF559float max_variance_squared = MAX(temp.Cov_VnVn, MAX(temp.Cov_VeVe, temp.Cov_VuVu));560if (is_positive(max_variance_squared)) {561state.have_speed_accuracy = true;562state.speed_accuracy = sqrt(max_variance_squared);563} else {564state.have_speed_accuracy = false;565}566break;567}568case AttEulerCov:569{570// yaw accuracy is taken from this message even though we actually calculate the yaw ourself (see AuxAntPositions below)571// this is OK based on the assumption that the calculation methods are similar and that inaccuracy arises from the sensor readings572if (get_type() == AP_GPS::GPS_Type::GPS_TYPE_SBF_DUAL_ANTENNA) {573const msg5939 &temp = sbf_msg.data.msg5939u;574575check_new_itow(temp.TOW, sbf_msg.length);576577constexpr double floatDNU = -2e-10f;578constexpr uint8_t errorBits = 0x8F; // Bits 0-1 are aux 1 baseline579// Bits 2-3 are aux 2 baseline580// Bit 7 is attitude not requested581#pragma GCC diagnostic push582#pragma GCC diagnostic ignored "-Wfloat-equal" // suppress -Wfloat-equal as it's false positive when testing for DNU values583if (((temp.Error & errorBits) == 0)584&& (temp.Cov_HeadHead != floatDNU)) {585#pragma GCC diagnostic pop586state.gps_yaw_accuracy = sqrtf(temp.Cov_HeadHead);587state.have_gps_yaw_accuracy = true;588} else {589state.gps_yaw_accuracy = false;590}591}592break;593}594case AuxAntPositions:595{596#if GPS_MOVING_BASELINE597if (get_type() == AP_GPS::GPS_Type::GPS_TYPE_SBF_DUAL_ANTENNA) {598// calculate yaw using reported antenna positions in earth-frame599// note that this calculation does not correct for the vehicle's roll and pitch meaning it is inaccurate at very high lean angles600const msg5942 &temp = sbf_msg.data.msg5942u;601check_new_itow(temp.TOW, sbf_msg.length);602if (temp.N > 0 && temp.ant1.Error == 0 && temp.ant1.AmbiguityType == 0) {603// valid RTK integer fix604const float rel_heading_deg = degrees(atan2f(temp.ant1.DeltaEast, temp.ant1.DeltaNorth));605calculate_moving_base_yaw(rel_heading_deg,606Vector3f(temp.ant1.DeltaNorth, temp.ant1.DeltaEast, temp.ant1.DeltaUp).length(),607-temp.ant1.DeltaUp);608}609}610#endif611break;612}613case BaseVectorGeod:614{615#pragma GCC diagnostic push616#pragma GCC diagnostic ignored "-Wfloat-equal" // suppress -Wfloat-equal as it's false positive when testing for DNU values617const msg4028 &temp = sbf_msg.data.msg4028u;618619// just breakout any consts we need for Do Not Use (DNU) reasons620constexpr double doubleDNU = -2e-10;621constexpr uint16_t uint16DNU = 65535;622623check_new_itow(temp.TOW, sbf_msg.length);624625if (temp.N == 0) { // no sub blocks so just bail, we can't do anything useful here626state.rtk_num_sats = 0;627state.rtk_age_ms = 0;628state.rtk_baseline_y_mm = 0;629state.rtk_baseline_x_mm = 0;630state.rtk_baseline_z_mm = 0;631break;632}633634state.rtk_num_sats = temp.info.NrSV;635636state.rtk_age_ms = (temp.info.CorrAge != 65535) ? ((uint32_t)temp.info.CorrAge) * 10 : 0;637638// copy the position as long as the data isn't DNU, we require NED, and heading before accepting any of it639if ((temp.info.DeltaEast != doubleDNU) && (temp.info.DeltaNorth != doubleDNU) && (temp.info.DeltaUp != doubleDNU) &&640(temp.info.Azimuth != uint16DNU)) {641642state.rtk_baseline_y_mm = temp.info.DeltaEast * 1e3;643state.rtk_baseline_x_mm = temp.info.DeltaNorth * 1e3;644state.rtk_baseline_z_mm = temp.info.DeltaUp * -1e3;645646#if GPS_MOVING_BASELINE647// copy the baseline data as a yaw source648if (option_set(AP_GPS::DriverOptions::SBF_UseBaseForYaw)) {649calculate_moving_base_yaw(temp.info.Azimuth * 0.01f + 180.0f,650Vector3f(temp.info.DeltaNorth, temp.info.DeltaEast, temp.info.DeltaUp).length(),651-temp.info.DeltaUp);652}653#endif // GPS_MOVING_BASELINE654655} else if (option_set(AP_GPS::DriverOptions::SBF_UseBaseForYaw)) {656state.rtk_baseline_y_mm = 0;657state.rtk_baseline_x_mm = 0;658state.rtk_baseline_z_mm = 0;659state.have_gps_yaw = false;660}661662#pragma GCC diagnostic pop663break;664}665}666667return false;668}669670void AP_GPS_SBF::broadcast_configuration_failure_reason(void) const671{672if (gps._auto_config != AP_GPS::GPS_AUTO_CONFIG_DISABLE &&673config_step != Config_State::Complete) {674GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GPS %u: SBF is not fully configured (%u/%u/%u/%u)",675state.instance + 1,676(unsigned)config_step,677_init_blob_index,678(unsigned)ARRAY_SIZE(_initialisation_blob),679(unsigned)ARRAY_SIZE(sbas_on_blob));680}681}682683bool AP_GPS_SBF::is_configured (void) const {684return ((gps._auto_config == AP_GPS::GPS_AUTO_CONFIG_DISABLE) ||685(config_step == Config_State::Complete) ||AP_SIM_GPS_SBF_ENABLED);686}687688bool AP_GPS_SBF::is_healthy (void) const {689return (RxError & RX_ERROR_MASK) == 0;690}691692void AP_GPS_SBF::mount_disk (void) const {693const char* command = "emd, DSK1, Mount\n";694Debug("Mounting disk");695port->write((const uint8_t*)command, strlen(command));696}697698void AP_GPS_SBF::unmount_disk (void) const {699const char* command = "emd, DSK1, Unmount\n";700GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "SBF unmounting disk");701port->write((const uint8_t*)command, strlen(command));702}703704bool AP_GPS_SBF::prepare_for_arming(void) {705bool is_logging = true; // assume that its logging until proven otherwise706if (gps._raw_data) {707if (!(RxState & SBF_DISK_MOUNTED)){708is_logging = false;709GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GPS %d: SBF disk is not mounted", state.instance + 1);710711// simply attempt to mount the disk, no need to check if the command was712// ACK/NACK'd as we don't continuously attempt to remount the disk713GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GPS %d: Attempting to mount disk", state.instance + 1);714mount_disk();715// reset the flag to indicate if we should be logging716_has_been_armed = false;717}718else if (RxState & SBF_DISK_FULL) {719is_logging = false;720GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GPS %d: SBF disk is full", state.instance + 1);721}722else if (!(RxState & SBF_DISK_ACTIVITY)) {723is_logging = false;724GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GPS %d: SBF is not currently logging", state.instance + 1);725}726}727728return is_logging;729}730731#endif732733734