Browse Source

AP_NavEKF3: 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
0443c8561b
  1. 4
      libraries/AP_NavEKF3/AP_NavEKF3.cpp
  2. 3
      libraries/AP_NavEKF3/AP_NavEKF3.h
  3. 7
      libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp
  4. 3
      libraries/AP_NavEKF3/AP_NavEKF3_core.h

4
libraries/AP_NavEKF3/AP_NavEKF3.cpp

@ -1776,10 +1776,10 @@ void NavEKF3::getFilterStatus(nav_filter_status &status) const @@ -1776,10 +1776,10 @@ void NavEKF3::getFilterStatus(nav_filter_status &status) const
}
// send an EKF_STATUS_REPORT message to GCS
void NavEKF3::send_status_report(mavlink_channel_t chan) const
void NavEKF3::send_status_report(GCS_MAVLINK &link) const
{
if (core) {
core[primary].send_status_report(chan);
core[primary].send_status_report(link);
}
}

3
libraries/AP_NavEKF3/AP_NavEKF3.h

@ -22,7 +22,6 @@ @@ -22,7 +22,6 @@
#include <AP_Common/Location.h>
#include <AP_Math/AP_Math.h>
#include <AP_Param/AP_Param.h>
#include <GCS_MAVLink/GCS_MAVLink.h>
#include <AP_NavEKF/AP_Nav_Common.h>
#include <AP_NavEKF/AP_NavEKF_Source.h>
@ -277,7 +276,7 @@ public: @@ -277,7 +276,7 @@ public:
void getFilterStatus(nav_filter_status &status) const;
// send an EKF_STATUS_REPORT message to GCS
void send_status_report(mavlink_channel_t chan) const;
void send_status_report(class GCS_MAVLINK &link) const;
// provides the height limit to be observed by the control loops
// returns false if no height limiting is required

7
libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp

@ -3,6 +3,7 @@ @@ -3,6 +3,7 @@
#include "AP_NavEKF3.h"
#include "AP_NavEKF3_core.h"
#include <AP_DAL/AP_DAL.h>
#include <GCS_MAVLink/GCS.h>
// Check basic filter health metrics and return a consolidated health status
bool NavEKF3_core::healthy(void) const
@ -525,8 +526,9 @@ void NavEKF3_core::getFilterStatus(nav_filter_status &status) const @@ -525,8 +526,9 @@ void NavEKF3_core::getFilterStatus(nav_filter_status &status) const
status = filterStatus;
}
#if HAL_GCS_ENABLED
// send an EKF_STATUS message to GCS
void NavEKF3_core::send_status_report(mavlink_channel_t chan) const
void NavEKF3_core::send_status_report(GCS_MAVLINK &link) const
{
// prepare flags
uint16_t flags = 0;
@ -585,8 +587,9 @@ void NavEKF3_core::send_status_report(mavlink_channel_t chan) const @@ -585,8 +587,9 @@ void NavEKF3_core::send_status_report(mavlink_channel_t chan) const
const float mag_max = fmaxF(fmaxF(magVar.x,magVar.y),magVar.z);
// send message
mavlink_msg_ekf_status_report_send(chan, flags, velVar, posVar, hgtVar, mag_max, temp, tasVar);
mavlink_msg_ekf_status_report_send(link.get_chan(), flags, velVar, posVar, hgtVar, mag_max, temp, tasVar);
}
#endif // HAL_GCS_ENABLED
// report the reason for why the backend is refusing to initialise
const char *NavEKF3_core::prearm_failure_reason(void) const

3
libraries/AP_NavEKF3/AP_NavEKF3_core.h

@ -32,7 +32,6 @@ @@ -32,7 +32,6 @@
#include <AP_NavEKF/AP_NavEKF_Source.h>
#include <AP_NavEKF/EKF_Buffer.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
#include <GCS_MAVLink/GCS_MAVLink.h>
#include <AP_DAL/AP_DAL.h>
#include "AP_NavEKF/EKFGSF_yaw.h"
@ -352,7 +351,7 @@ public: @@ -352,7 +351,7 @@ public:
void getFilterStatus(nav_filter_status &status) const;
// send an EKF_STATUS_REPORT message to GCS
void send_status_report(mavlink_channel_t chan) const;
void send_status_report(class GCS_MAVLINK &link) const;
// provides the height limit to be observed by the control loops
// returns false if no height limiting is required

Loading…
Cancel
Save