AP_AHRS: use const reference not pointers for locations

this makes life easier for the new AP_Mission library

Pair-Programmed-With: Brandon Jones <brnjones@gmail.com>
This commit is contained in:
Andrew Tridgell 2013-08-05 10:16:31 +10:00
parent f3b3e23bbc
commit 0d36832b82
4 changed files with 9 additions and 9 deletions

View File

@ -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;

View File

@ -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) {

View File

@ -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;
}

View File

@ -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);