mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: rename AP_AHRS::get_position to get_location
This commit is contained in:
parent
8461c11742
commit
d1acc5df31
|
@ -1491,7 +1491,7 @@ int16_t GCS_MAVLINK_Copter::high_latency_target_altitude() const
|
|||
{
|
||||
AP_AHRS &ahrs = AP::ahrs();
|
||||
struct Location global_position_current;
|
||||
UNUSED_RESULT(ahrs.get_position(global_position_current));
|
||||
UNUSED_RESULT(ahrs.get_location(global_position_current));
|
||||
|
||||
//return units are m
|
||||
if (copter.ap.initialised) {
|
||||
|
|
|
@ -179,7 +179,7 @@ bool AP_Avoidance_Copter::handle_avoidance_vertical(const AP_Avoidance::Obstacle
|
|||
// decide on whether we should climb or descend
|
||||
bool should_climb = false;
|
||||
Location my_loc;
|
||||
if (AP::ahrs().get_position(my_loc)) {
|
||||
if (AP::ahrs().get_location(my_loc)) {
|
||||
should_climb = my_loc.alt > obstacle->_location.alt;
|
||||
}
|
||||
|
||||
|
|
|
@ -24,7 +24,7 @@ void Copter::set_home_to_current_location_inflight() {
|
|||
// get current location from EKF
|
||||
Location temp_loc;
|
||||
Location ekf_origin;
|
||||
if (ahrs.get_position(temp_loc) && ahrs.get_origin(ekf_origin)) {
|
||||
if (ahrs.get_location(temp_loc) && ahrs.get_origin(ekf_origin)) {
|
||||
temp_loc.alt = ekf_origin.alt;
|
||||
if (!set_home(temp_loc, false)) {
|
||||
return;
|
||||
|
@ -40,7 +40,7 @@ void Copter::set_home_to_current_location_inflight() {
|
|||
bool Copter::set_home_to_current_location(bool lock) {
|
||||
// get current location from EKF
|
||||
Location temp_loc;
|
||||
if (ahrs.get_position(temp_loc)) {
|
||||
if (ahrs.get_location(temp_loc)) {
|
||||
if (!set_home(temp_loc, lock)) {
|
||||
return false;
|
||||
}
|
||||
|
|
|
@ -8,7 +8,7 @@ void Copter::read_inertia()
|
|||
|
||||
// pull position from ahrs
|
||||
Location loc;
|
||||
ahrs.get_position(loc);
|
||||
ahrs.get_location(loc);
|
||||
current_loc.lat = loc.lat;
|
||||
current_loc.lng = loc.lng;
|
||||
|
||||
|
|
Loading…
Reference in New Issue