2021-03-24 03:24:01 -03:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
/*
|
2023-10-11 04:41:52 -03:00
|
|
|
support for serial connected AHRS systems
|
2021-03-24 03:24:01 -03:00
|
|
|
*/
|
|
|
|
|
|
|
|
#pragma once
|
|
|
|
|
2023-04-24 06:54:51 -03:00
|
|
|
#include "AP_ExternalAHRS_config.h"
|
|
|
|
|
|
|
|
#if AP_EXTERNAL_AHRS_VECTORNAV_ENABLED
|
2021-03-24 03:24:01 -03:00
|
|
|
|
2023-04-24 06:54:51 -03:00
|
|
|
#include "AP_ExternalAHRS_backend.h"
|
2021-03-24 03:24:01 -03:00
|
|
|
|
|
|
|
class AP_ExternalAHRS_VectorNav : public AP_ExternalAHRS_backend {
|
|
|
|
|
|
|
|
public:
|
|
|
|
AP_ExternalAHRS_VectorNav(AP_ExternalAHRS *frontend, AP_ExternalAHRS::state_t &state);
|
|
|
|
|
|
|
|
// get serial port number, -1 for not enabled
|
|
|
|
int8_t get_port(void) const override;
|
|
|
|
|
|
|
|
// accessors for AP_AHRS
|
|
|
|
bool healthy(void) const override;
|
|
|
|
bool initialised(void) const override;
|
|
|
|
bool pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const override;
|
|
|
|
void get_filter_status(nav_filter_status &status) const override;
|
2022-07-08 01:15:35 -03:00
|
|
|
void send_status_report(class GCS_MAVLINK &link) const override;
|
2021-03-24 03:24:01 -03:00
|
|
|
|
|
|
|
// check for new data
|
|
|
|
void update() override {
|
|
|
|
check_uart();
|
|
|
|
}
|
|
|
|
|
2022-12-19 12:27:51 -04:00
|
|
|
// Get model/type name
|
|
|
|
const char* get_name() const override;
|
|
|
|
|
2021-03-24 03:24:01 -03:00
|
|
|
private:
|
|
|
|
AP_HAL::UARTDriver *uart;
|
|
|
|
int8_t port_num;
|
2022-12-19 12:27:51 -04:00
|
|
|
bool setup_complete;
|
2021-03-24 03:24:01 -03:00
|
|
|
uint32_t baudrate;
|
|
|
|
|
|
|
|
void update_thread();
|
|
|
|
bool check_uart();
|
|
|
|
|
|
|
|
void process_packet1(const uint8_t *b);
|
|
|
|
void process_packet2(const uint8_t *b);
|
2022-12-19 12:27:51 -04:00
|
|
|
void process_packet_VN_100(const uint8_t *b);
|
|
|
|
void wait_register_responce(const uint8_t register_num);
|
2021-03-24 03:24:01 -03:00
|
|
|
|
|
|
|
uint8_t *pktbuf;
|
|
|
|
uint16_t pktoffset;
|
|
|
|
uint16_t bufsize;
|
|
|
|
|
|
|
|
struct VN_packet1 *last_pkt1;
|
|
|
|
struct VN_packet2 *last_pkt2;
|
|
|
|
|
|
|
|
uint32_t last_pkt1_ms;
|
|
|
|
uint32_t last_pkt2_ms;
|
2022-12-19 12:27:51 -04:00
|
|
|
|
|
|
|
enum class TYPE {
|
|
|
|
VN_300,
|
|
|
|
VN_100,
|
|
|
|
} type;
|
|
|
|
|
|
|
|
char model_name[25];
|
|
|
|
|
|
|
|
// NMEA parsing for setup
|
|
|
|
bool decode(char c);
|
|
|
|
bool decode_latest_term();
|
|
|
|
struct NMEA_parser {
|
|
|
|
char term[25]; // buffer for the current term within the current sentence
|
|
|
|
uint8_t term_offset; // offset within the _term buffer where the next character should be placed
|
|
|
|
uint8_t term_number; // term index within the current sentence
|
|
|
|
uint8_t checksum; // checksum accumulator
|
|
|
|
bool term_is_checksum; // current term is the checksum
|
|
|
|
bool sentence_valid; // is current sentence valid so far
|
|
|
|
bool sentence_done; // true if this sentence has already been decoded
|
|
|
|
uint8_t register_number; // VectorNAV register number were reading
|
|
|
|
} nmea;
|
|
|
|
|
2021-03-24 03:24:01 -03:00
|
|
|
};
|
|
|
|
|
2023-04-24 06:54:51 -03:00
|
|
|
#endif // AP_EXTERNAL_AHRS_VECTORNAV_ENABLED
|