mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_AHRS: avoid using struct Location
clang reports this could be a problem when compiling under some EABIs. Remove it from most places as it is just noise, replace with class where we want to avoid including Location.h
This commit is contained in:
parent
44d0172f83
commit
7fa0b75d48
@ -681,7 +681,7 @@ void AP_AHRS::reset()
|
||||
}
|
||||
|
||||
// dead-reckoning support
|
||||
bool AP_AHRS::get_location(struct Location &loc) const
|
||||
bool AP_AHRS::get_location(Location &loc) const
|
||||
{
|
||||
switch (active_EKF_type()) {
|
||||
case EKFType::NONE:
|
||||
@ -1158,7 +1158,7 @@ bool AP_AHRS::get_secondary_quaternion(Quaternion &quat) const
|
||||
}
|
||||
|
||||
// return secondary position solution if available
|
||||
bool AP_AHRS::get_secondary_position(struct Location &loc) const
|
||||
bool AP_AHRS::get_secondary_position(Location &loc) const
|
||||
{
|
||||
EKFType secondary_ekf_type;
|
||||
if (!get_secondary_EKF_type(secondary_ekf_type)) {
|
||||
|
@ -89,7 +89,7 @@ public:
|
||||
void reset();
|
||||
|
||||
// dead-reckoning support
|
||||
bool get_location(struct Location &loc) const;
|
||||
bool get_location(Location &loc) const;
|
||||
|
||||
// get latest altitude estimate above ground level in meters and validity flag
|
||||
bool get_hagl(float &hagl) const WARN_IF_UNUSED;
|
||||
@ -174,7 +174,7 @@ public:
|
||||
bool get_secondary_quaternion(Quaternion &quat) const;
|
||||
|
||||
// return secondary position solution if available
|
||||
bool get_secondary_position(struct Location &loc) const;
|
||||
bool get_secondary_position(Location &loc) const;
|
||||
|
||||
// EKF has a better ground speed vector estimate
|
||||
Vector2f groundspeed_vector();
|
||||
@ -433,7 +433,7 @@ public:
|
||||
|
||||
// get the home location. This is const to prevent any changes to
|
||||
// home without telling AHRS about the change
|
||||
const struct Location &get_home(void) const {
|
||||
const Location &get_home(void) const {
|
||||
return _home;
|
||||
}
|
||||
|
||||
@ -718,7 +718,7 @@ private:
|
||||
*/
|
||||
void load_watchdog_home();
|
||||
bool _checked_watchdog_home;
|
||||
struct Location _home;
|
||||
Location _home;
|
||||
bool _home_is_set :1;
|
||||
bool _home_locked :1;
|
||||
|
||||
|
@ -111,7 +111,7 @@ public:
|
||||
|
||||
// get our current position estimate. Return true if a position is available,
|
||||
// otherwise false. This call fills in lat, lng and alt
|
||||
virtual bool get_location(struct Location &loc) const WARN_IF_UNUSED = 0;
|
||||
virtual bool get_location(Location &loc) const WARN_IF_UNUSED = 0;
|
||||
|
||||
// get latest altitude estimate above ground level in meters and validity flag
|
||||
virtual bool get_hagl(float &height) const WARN_IF_UNUSED { return false; }
|
||||
@ -193,10 +193,10 @@ public:
|
||||
}
|
||||
|
||||
//
|
||||
virtual bool set_origin(const struct Location &loc) {
|
||||
virtual bool set_origin(const Location &loc) {
|
||||
return false;
|
||||
}
|
||||
virtual bool get_origin(struct Location &ret) const = 0;
|
||||
virtual bool get_origin(Location &ret) const = 0;
|
||||
|
||||
// return a position relative to origin in meters, North/East/Down
|
||||
// order. This will only be accurate if have_inertial_nav() is
|
||||
|
@ -1022,7 +1022,7 @@ void AP_AHRS_DCM::estimate_wind(void)
|
||||
|
||||
// return our current position estimate using
|
||||
// dead-reckoning or GPS
|
||||
bool AP_AHRS_DCM::get_location(struct Location &loc) const
|
||||
bool AP_AHRS_DCM::get_location(Location &loc) const
|
||||
{
|
||||
loc.lat = _last_lat;
|
||||
loc.lng = _last_lng;
|
||||
|
@ -61,7 +61,7 @@ public:
|
||||
}
|
||||
|
||||
// dead-reckoning support
|
||||
virtual bool get_location(struct Location &loc) const override;
|
||||
virtual bool get_location(Location &loc) const override;
|
||||
|
||||
// status reporting
|
||||
float get_error_rp() const {
|
||||
|
@ -9,7 +9,7 @@
|
||||
void AP_AHRS::Write_AHRS2() const
|
||||
{
|
||||
Vector3f euler;
|
||||
struct Location loc;
|
||||
Location loc;
|
||||
Quaternion quat;
|
||||
if (!get_secondary_attitude(euler) || !get_secondary_position(loc) || !get_secondary_quaternion(quat)) {
|
||||
return;
|
||||
|
@ -4,7 +4,7 @@
|
||||
|
||||
#include "AP_AHRS.h"
|
||||
|
||||
bool AP_AHRS_SIM::get_location(struct Location &loc) const
|
||||
bool AP_AHRS_SIM::get_location(Location &loc) const
|
||||
{
|
||||
if (_sitl == nullptr) {
|
||||
return false;
|
||||
|
@ -61,7 +61,7 @@ public:
|
||||
void reset() override { return; }
|
||||
|
||||
// dead-reckoning support
|
||||
virtual bool get_location(struct Location &loc) const override;
|
||||
virtual bool get_location(Location &loc) const override;
|
||||
|
||||
// get latest altitude estimate above ground level in meters and validity flag
|
||||
bool get_hagl(float &hagl) const override WARN_IF_UNUSED;
|
||||
|
@ -85,7 +85,7 @@ public:
|
||||
wrappers around ahrs functions which pass-thru directly. See
|
||||
AP_AHRS.h for description of each function
|
||||
*/
|
||||
bool get_location(struct Location &loc) const WARN_IF_UNUSED {
|
||||
bool get_location(Location &loc) const WARN_IF_UNUSED {
|
||||
return ahrs.get_location(loc);
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user