AP_ExternalAHRS: stop using GCS_MAVLINK.h in header files

... by passing through a reference to a link object instead
This commit is contained in:
Peter Barker 2022-07-08 14:15:35 +10:00 committed by Andrew Tridgell
parent a840af1ff5
commit 74e651e5d7
7 changed files with 10 additions and 14 deletions

View File

@ -194,10 +194,10 @@ Vector3f AP_ExternalAHRS::get_accel(void)
}
// send an EKF_STATUS message to GCS
void AP_ExternalAHRS::send_status_report(mavlink_channel_t chan) const
void AP_ExternalAHRS::send_status_report(GCS_MAVLINK &link) const
{
if (backend) {
backend->send_status_report(chan);
backend->send_status_report(link);
}
}

View File

@ -29,8 +29,6 @@
#if HAL_EXTERNAL_AHRS_ENABLED
#include <GCS_MAVLink/GCS_MAVLink.h>
class AP_ExternalAHRS_backend;
class AP_ExternalAHRS {
@ -91,7 +89,7 @@ public:
void get_filter_status(nav_filter_status &status) const;
Vector3f get_gyro(void);
Vector3f get_accel(void);
void send_status_report(mavlink_channel_t chan) const;
void send_status_report(class GCS_MAVLINK &link) const;
// update backend
void update();

View File

@ -491,7 +491,7 @@ void AP_ExternalAHRS_LORD::get_filter_status(nav_filter_status &status) const
}
}
void AP_ExternalAHRS_LORD::send_status_report(mavlink_channel_t chan) const
void AP_ExternalAHRS_LORD::send_status_report(GCS_MAVLINK &link) const
{
// prepare flags
uint16_t flags = 0;
@ -536,7 +536,7 @@ void AP_ExternalAHRS_LORD::send_status_report(mavlink_channel_t chan) const
const float pos_gate = 4; // represents hz value data is posted at
const float hgt_gate = 4; // represents hz value data is posted at
const float mag_var = 0; //we may need to change this to be like the other gates, set to 0 because mag is ignored by the ins filter in vectornav
mavlink_msg_ekf_status_report_send(chan, flags,
mavlink_msg_ekf_status_report_send(link.get_chan(), flags,
gnss_data.speed_accuracy/vel_gate, gnss_data.horizontal_position_accuracy/pos_gate, gnss_data.vertical_position_accuracy/hgt_gate,
mag_var, 0, 0);

View File

@ -40,7 +40,7 @@ public:
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;
void send_status_report(mavlink_channel_t chan) const override;
void send_status_report(class GCS_MAVLINK &link) const override;
// check for new data
void update() override {

View File

@ -417,7 +417,7 @@ void AP_ExternalAHRS_VectorNav::get_filter_status(nav_filter_status &status) con
}
// send an EKF_STATUS message to GCS
void AP_ExternalAHRS_VectorNav::send_status_report(mavlink_channel_t chan) const
void AP_ExternalAHRS_VectorNav::send_status_report(GCS_MAVLINK &link) const
{
if (!last_pkt1) {
return;
@ -466,7 +466,7 @@ void AP_ExternalAHRS_VectorNav::send_status_report(mavlink_channel_t chan) const
const float pos_gate = 5;
const float hgt_gate = 5;
const float mag_var = 0;
mavlink_msg_ekf_status_report_send(chan, flags,
mavlink_msg_ekf_status_report_send(link.get_chan(), flags,
pkt1.velU/vel_gate, pkt1.posU/pos_gate, pkt1.posU/hgt_gate,
mag_var, 0, 0);
}

View File

@ -22,8 +22,6 @@
#if HAL_EXTERNAL_AHRS_ENABLED
#include <GCS_MAVLink/GCS_MAVLink.h>
class AP_ExternalAHRS_VectorNav : public AP_ExternalAHRS_backend {
public:
@ -37,7 +35,7 @@ public:
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;
void send_status_report(mavlink_channel_t chan) const override;
void send_status_report(class GCS_MAVLINK &link) const override;
// check for new data
void update() override {

View File

@ -34,7 +34,7 @@ public:
virtual bool initialised(void) const = 0;
virtual bool pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const = 0;
virtual void get_filter_status(nav_filter_status &status) const {}
virtual void send_status_report(mavlink_channel_t chan) const {}
virtual void send_status_report(class GCS_MAVLINK &link) const {}
// check for new data
virtual void update() = 0;