Path: blob/master/libraries/AP_ExternalAHRS/AP_ExternalAHRS_SensAItion.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.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#pragma once1617#include "AP_ExternalAHRS_config.h"1819#if AP_EXTERNAL_AHRS_SENSAITION_ENABLED2021#include "AP_ExternalAHRS_backend.h"22#include "AP_ExternalAHRS_SensAItion_Parser.h"2324/*25This class is the interface to Kebni's SensAItion range of inertial navigation26sensors, which can provide raw sensor data and/or a sensor fusion solution.27*/28class AP_ExternalAHRS_SensAItion : public AP_ExternalAHRS_backend29{30public:31AP_ExternalAHRS_SensAItion(AP_ExternalAHRS *frontend, AP_ExternalAHRS::state_t &_state);3233// Hardware Identification34int8_t get_port() const override;35const char* get_name() const override;3637// Health & Status Interface38bool healthy() const override;39bool initialised() const override;40bool pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const override;41void get_filter_status(nav_filter_status &status) const override;42bool get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const override;4344// GPS Interface45uint8_t num_gps_sensors() const override;4647// Main Loop48void update() override49{50check_uart();51}5253private:54mutable HAL_Semaphore sem_handle;5556// The member variables below are accessed both from our own57// thread and the main thread and should be protected58// by sem_handle!59// =======================================================60AP_ExternalAHRS::ins_data_message_t ins;61AP_ExternalAHRS::mag_data_message_t mag;62AP_ExternalAHRS::baro_data_message_t baro;63AP_ExternalAHRS::gps_data_message_t gps;64AP_ExternalAHRS_SensAItion_Parser parser;6566// UART67AP_HAL::UARTDriver *uart;68uint8_t buffer[AP_ExternalAHRS_SensAItion_Parser::MAX_PACKET_SIZE];6970bool setup_complete;7172// End of member variables protected by sem_handle73// =======================================================7475// These states are accessed by the public accessor functions,76// so to avoid slowing them down by waiting for sem_handle,77// we use the included semaphore to protect access to them.78// USAGE:79// - If taking both semaphores, always take sem_handle first!80// - Hold this semaphore only while accessing the driver state81// to minimize the waiting time for it!82struct {83mutable HAL_Semaphore semaphore;8485uint32_t last_imu_pkt_ms;86uint32_t last_ins_pkt_ms; // Only used in INS mode87uint32_t last_quat_pkt_ms; // Only used in INS mode88uint32_t last_baro_update_ms;8990// Last known values from INS packet (Packet 2)91uint8_t last_alignment_status;92uint8_t last_gnss1_fix;93uint8_t last_gnss2_fix;94uint8_t last_sensor_valid;95float last_h_pos_quality = 999.9f;96float last_v_pos_quality = 999.9f;97float last_vel_quality = 999.9f;98uint32_t last_error_flags;99} driver_state;100101// Read-only after construction, do not need semaphore102bool ins_mode_enabled = false;103uint32_t baudrate = 460800;104int8_t port_num = -1;105106void update_thread();107bool check_uart();108109void handle_imu(const AP_ExternalAHRS_SensAItion_Parser::Measurement& meas, uint32_t now_ms);110void handle_ahrs(const AP_ExternalAHRS_SensAItion_Parser::Measurement& meas, uint32_t now_ms);111void handle_ins(const AP_ExternalAHRS_SensAItion_Parser::Measurement& meas, uint32_t now_ms);112};113#endif // AP_EXTERNAL_AHRS_SENSAITION_ENABLED114115116