diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index f921b744bc..8b57bc89d8 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -203,7 +203,7 @@ Vector2f AP_AHRS::groundspeed_vector(void) /* get position projected by groundspeed and heading */ -bool AP_AHRS::get_projected_position(struct Location *loc) +bool AP_AHRS::get_projected_position(struct Location &loc) { if (!get_position(loc)) { return false; diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index 04a1e2e9b3..9ace4e6814 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -128,18 +128,18 @@ public: // dead-reckoning. Return true if a position is available, // otherwise false. This only updates the lat and lng fields // of the Location - virtual bool get_position(struct Location *loc) { + virtual bool get_position(struct Location &loc) { if (!_gps || _gps->status() <= GPS::NO_FIX) { return false; } - loc->lat = _gps->latitude; - loc->lng = _gps->longitude; + loc.lat = _gps->latitude; + loc.lng = _gps->longitude; return true; } // get our projected position, based on our GPS position plus // heading and ground speed - bool get_projected_position(struct Location *loc); + bool get_projected_position(struct Location &loc); // return a wind estimation vector, in m/s virtual Vector3f wind_estimate(void) { diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.cpp b/libraries/AP_AHRS/AP_AHRS_DCM.cpp index e8f033476d..3039036af8 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.cpp +++ b/libraries/AP_AHRS/AP_AHRS_DCM.cpp @@ -765,13 +765,13 @@ float AP_AHRS_DCM::get_error_yaw(void) // return our current position estimate using // dead-reckoning or GPS -bool AP_AHRS_DCM::get_position(struct Location *loc) +bool AP_AHRS_DCM::get_position(struct Location &loc) { if (!_have_position) { return false; } - loc->lat = _last_lat; - loc->lng = _last_lng; + loc.lat = _last_lat; + loc.lng = _last_lng; location_offset(loc, _position_offset_north, _position_offset_east); return true; } diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.h b/libraries/AP_AHRS/AP_AHRS_DCM.h index 3432c85c56..21ffc32927 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.h +++ b/libraries/AP_AHRS/AP_AHRS_DCM.h @@ -45,7 +45,7 @@ public: void reset(bool recover_eulers = false); // dead-reckoning support - bool get_position(struct Location *loc); + bool get_position(struct Location &loc); // status reporting float get_error_rp(void);