mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF2: stop using GCS_MAVLINK.h in header files
... by passing through a reference to a link object instead
This commit is contained in:
parent
74e651e5d7
commit
c46a50f428
|
@ -1274,10 +1274,10 @@ void NavEKF2::getFilterGpsStatus(nav_gps_status &status) const
|
||||||
}
|
}
|
||||||
|
|
||||||
// send an EKF_STATUS_REPORT message to GCS
|
// send an EKF_STATUS_REPORT message to GCS
|
||||||
void NavEKF2::send_status_report(mavlink_channel_t chan) const
|
void NavEKF2::send_status_report(GCS_MAVLINK &link) const
|
||||||
{
|
{
|
||||||
if (core) {
|
if (core) {
|
||||||
core[primary].send_status_report(chan);
|
core[primary].send_status_report(link);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -25,7 +25,6 @@
|
||||||
#include <AP_Common/Location.h>
|
#include <AP_Common/Location.h>
|
||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
#include <AP_Param/AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
|
||||||
#include <AP_NavEKF/AP_Nav_Common.h>
|
#include <AP_NavEKF/AP_Nav_Common.h>
|
||||||
|
|
||||||
class NavEKF2_core;
|
class NavEKF2_core;
|
||||||
|
@ -216,7 +215,7 @@ public:
|
||||||
void getFilterStatus(nav_filter_status &status) const;
|
void getFilterStatus(nav_filter_status &status) const;
|
||||||
|
|
||||||
// send an EKF_STATUS_REPORT message to GCS
|
// 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
|
// provides the height limit to be observed by the control loops
|
||||||
// returns false if no height limiting is required
|
// returns false if no height limiting is required
|
||||||
|
|
|
@ -3,6 +3,7 @@
|
||||||
#include "AP_NavEKF2_core.h"
|
#include "AP_NavEKF2_core.h"
|
||||||
#include <AP_DAL/AP_DAL.h>
|
#include <AP_DAL/AP_DAL.h>
|
||||||
#include <AP_AHRS/AP_AHRS.h>
|
#include <AP_AHRS/AP_AHRS.h>
|
||||||
|
#include <GCS_MAVLink/GCS.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
|
@ -492,8 +493,9 @@ void NavEKF2_core::getFilterGpsStatus(nav_gps_status &faults) const
|
||||||
faults.flags.bad_horiz_vel = gpsCheckStatus.bad_horiz_vel; // The GPS horizontal speed is excessive (check assumes the vehicle is static)
|
faults.flags.bad_horiz_vel = gpsCheckStatus.bad_horiz_vel; // The GPS horizontal speed is excessive (check assumes the vehicle is static)
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HAL_GCS_ENABLED
|
||||||
// send an EKF_STATUS message to GCS
|
// send an EKF_STATUS message to GCS
|
||||||
void NavEKF2_core::send_status_report(mavlink_channel_t chan) const
|
void NavEKF2_core::send_status_report(GCS_MAVLINK &link) const
|
||||||
{
|
{
|
||||||
// prepare flags
|
// prepare flags
|
||||||
uint16_t flags = 0;
|
uint16_t flags = 0;
|
||||||
|
@ -550,8 +552,9 @@ void NavEKF2_core::send_status_report(mavlink_channel_t chan) const
|
||||||
}
|
}
|
||||||
|
|
||||||
// send message
|
// 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
|
// report the reason for why the backend is refusing to initialise
|
||||||
const char *NavEKF2_core::prearm_failure_reason(void) const
|
const char *NavEKF2_core::prearm_failure_reason(void) const
|
||||||
|
|
|
@ -29,7 +29,6 @@
|
||||||
#include <AP_Math/vectorN.h>
|
#include <AP_Math/vectorN.h>
|
||||||
#include <AP_NavEKF/AP_NavEKF_core_common.h>
|
#include <AP_NavEKF/AP_NavEKF_core_common.h>
|
||||||
#include <AP_NavEKF/EKF_Buffer.h>
|
#include <AP_NavEKF/EKF_Buffer.h>
|
||||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
|
||||||
#include <AP_DAL/AP_DAL.h>
|
#include <AP_DAL/AP_DAL.h>
|
||||||
|
|
||||||
#include "AP_NavEKF/EKFGSF_yaw.h"
|
#include "AP_NavEKF/EKFGSF_yaw.h"
|
||||||
|
@ -247,7 +246,7 @@ public:
|
||||||
void getFilterStatus(nav_filter_status &status) const;
|
void getFilterStatus(nav_filter_status &status) const;
|
||||||
|
|
||||||
// send an EKF_STATUS_REPORT message to GCS
|
// 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
|
// provides the height limit to be observed by the control loops
|
||||||
// returns false if no height limiting is required
|
// returns false if no height limiting is required
|
||||||
|
|
Loading…
Reference in New Issue