mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: rename AP_AHRS::get_position to get_location
This commit is contained in:
parent
89b56f38f2
commit
03cde13b55
@ -45,7 +45,7 @@ void Rover::Log_Write_Depth()
|
||||
|
||||
// get position
|
||||
Location loc;
|
||||
IGNORE_RETURN(ahrs.get_position(loc));
|
||||
IGNORE_RETURN(ahrs.get_location(loc));
|
||||
|
||||
for (uint8_t i=0; i<rangefinder.num_sensors(); i++) {
|
||||
const AP_RangeFinder_Backend *s = rangefinder.get_backend(i);
|
||||
|
@ -263,7 +263,7 @@ void Rover::ahrs_update()
|
||||
ahrs.update();
|
||||
|
||||
// update position
|
||||
have_position = ahrs.get_position(current_loc);
|
||||
have_position = ahrs.get_location(current_loc);
|
||||
|
||||
// set home from EKF if necessary and possible
|
||||
if (!ahrs.home_is_set()) {
|
||||
|
@ -4,7 +4,7 @@
|
||||
bool Rover::set_home_to_current_location(bool lock)
|
||||
{
|
||||
Location temp_loc;
|
||||
if (ahrs.have_inertial_nav() && ahrs.get_position(temp_loc)) {
|
||||
if (ahrs.have_inertial_nav() && ahrs.get_location(temp_loc)) {
|
||||
if (!set_home(temp_loc, lock)) {
|
||||
return false;
|
||||
}
|
||||
@ -64,7 +64,7 @@ void Rover::update_home()
|
||||
}
|
||||
|
||||
Location loc{};
|
||||
if (!ahrs.get_position(loc)) {
|
||||
if (!ahrs.get_location(loc)) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user