Browse Source

AP_ExternalAHRS: stop using GCS_MAVLINK.h in header files

... by passing through a reference to a link object instead
master
Peter Barker 3 years ago committed by Andrew Tridgell
parent
commit
74e651e5d7
  1. 4
      libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp
  2. 4
      libraries/AP_ExternalAHRS/AP_ExternalAHRS.h
  3. 4
      libraries/AP_ExternalAHRS/AP_ExternalAHRS_LORD.cpp
  4. 2
      libraries/AP_ExternalAHRS/AP_ExternalAHRS_LORD.h
  5. 4
      libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp
  6. 4
      libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.h
  7. 2
      libraries/AP_ExternalAHRS/AP_ExternalAHRS_backend.h

4
libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp

@ -194,10 +194,10 @@ Vector3f AP_ExternalAHRS::get_accel(void)
} }
// send an EKF_STATUS message to GCS // 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) { if (backend) {
backend->send_status_report(chan); backend->send_status_report(link);
} }
} }

4
libraries/AP_ExternalAHRS/AP_ExternalAHRS.h

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

4
libraries/AP_ExternalAHRS/AP_ExternalAHRS_LORD.cpp

@ -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 // prepare flags
uint16_t flags = 0; 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 pos_gate = 4; // represents hz value data is posted at
const float hgt_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 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, gnss_data.speed_accuracy/vel_gate, gnss_data.horizontal_position_accuracy/pos_gate, gnss_data.vertical_position_accuracy/hgt_gate,
mag_var, 0, 0); mag_var, 0, 0);

2
libraries/AP_ExternalAHRS/AP_ExternalAHRS_LORD.h

@ -40,7 +40,7 @@ public:
bool initialised(void) const override; bool initialised(void) const override;
bool pre_arm_check(char *failure_msg, uint8_t failure_msg_len) 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 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 // check for new data
void update() override { void update() override {

4
libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp

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

4
libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.h

@ -22,8 +22,6 @@
#if HAL_EXTERNAL_AHRS_ENABLED #if HAL_EXTERNAL_AHRS_ENABLED
#include <GCS_MAVLink/GCS_MAVLink.h>
class AP_ExternalAHRS_VectorNav : public AP_ExternalAHRS_backend { class AP_ExternalAHRS_VectorNav : public AP_ExternalAHRS_backend {
public: public:
@ -37,7 +35,7 @@ public:
bool initialised(void) const override; bool initialised(void) const override;
bool pre_arm_check(char *failure_msg, uint8_t failure_msg_len) 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 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 // check for new data
void update() override { void update() override {

2
libraries/AP_ExternalAHRS/AP_ExternalAHRS_backend.h

@ -34,7 +34,7 @@ public:
virtual bool initialised(void) const = 0; virtual bool initialised(void) const = 0;
virtual bool pre_arm_check(char *failure_msg, uint8_t failure_msg_len) 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 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 // check for new data
virtual void update() = 0; virtual void update() = 0;

Loading…
Cancel
Save