Path: blob/master/libraries/AP_ExternalAHRS/AP_ExternalAHRS_GSOF.h
13808 views
/*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.5This program is distributed in the hope that it will be useful,6but WITHOUT ANY WARRANTY; without even the implied warranty of7MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the8GNU General Public License for more details.9You should have received a copy of the GNU General Public License10along with this program. If not, see <http://www.gnu.org/licenses/>.11*/12/*13Support for Trimble PX-1 GNSS-RTX-INS.14*/151617#pragma once1819#include "AP_ExternalAHRS_config.h"2021#if AP_EXTERNAL_AHRS_GSOF_ENABLED2223#include "AP_ExternalAHRS_backend.h"24#include <AP_HAL/AP_HAL.h>25#include <AP_GSOF/AP_GSOF.h>2627class AP_ExternalAHRS_GSOF: public AP_ExternalAHRS_backend, public AP_GSOF28{29public:3031AP_ExternalAHRS_GSOF(AP_ExternalAHRS *frontend, AP_ExternalAHRS::state_t &state);3233// Get model/type name34const char* get_name() const override;3536// get serial port number, -1 for not enabled37int8_t get_port() const override;3839// accessors for AP_AHRS40bool healthy(void) const override;41bool initialised(void) const override;42bool pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const override;43void get_filter_status(nav_filter_status &status) const override;44bool get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const override;454647// check for new data48void update() override49{50// This driver update runs in a dedicated thread, skip this.51};5253protected:5455uint8_t num_gps_sensors(void) const override56{57return 1;58}5960private:6162void update_thread();63void check_initialise_state();64bool times_healthy() const;65bool filter_healthy() const;66void post_filter() const;6768AP_HAL::UARTDriver *uart;69int8_t port_num;70uint32_t baudrate;7172HAL_Semaphore sem;7374// Used to monitor initialization state.75bool last_init_state;7677// The last time we received a message from the GNSS78// containing AP_GSOF::POS_TIME.79uint32_t last_pos_time_ms;80// The last time we received a message from the GNSS81// containing AP_GSOF::INS_FULL_NAV.82uint32_t last_ins_full_nav_ms;83// The last time we received a message from the GNSS84// containing AP_GSOF::INS_RMS.85uint32_t last_ins_rms_ms;86// The last time we received a message from the GNSS87// containing AP_GSOF::LLH_MSL.88uint32_t last_llh_msl_ms;8990// The last calculated undulation, which is computed only at the rate both inputs are received.91// The undulation is necessary to convert the INS full nav solution from ellipsoid to MSL altitude.92double undulation;9394AP_ExternalAHRS::gps_data_message_t gps_data;9596};9798#endif // AP_EXTERNAL_AHRS_GSOF_ENABLED99100101