Browse Source

AP_Avoidance: rename AP_AHRS::get_position to get_location

gps-1.3.1
Peter Barker 3 years ago committed by Andrew Tridgell
parent
commit
313ed7fc71
  1. 6
      libraries/AP_Avoidance/AP_Avoidance.cpp

6
libraries/AP_Avoidance/AP_Avoidance.cpp

@ -457,7 +457,7 @@ void AP_Avoidance::check_for_threats() @@ -457,7 +457,7 @@ void AP_Avoidance::check_for_threats()
const AP_AHRS &_ahrs = AP::ahrs();
Location my_loc;
if (!_ahrs.get_position(my_loc)) {
if (!_ahrs.get_location(my_loc)) {
// if we don't know our own location we can't determine any threat level
return;
}
@ -542,7 +542,7 @@ void AP_Avoidance::handle_avoidance_local(AP_Avoidance::Obstacle *threat) @@ -542,7 +542,7 @@ void AP_Avoidance::handle_avoidance_local(AP_Avoidance::Obstacle *threat)
action = (MAV_COLLISION_ACTION)_fail_action.get();
Location my_loc;
if (action != MAV_COLLISION_ACTION_NONE && _fail_altitude_minimum > 0 &&
AP::ahrs().get_position(my_loc) && ((my_loc.alt*0.01f) < _fail_altitude_minimum)) {
AP::ahrs().get_location(my_loc) && ((my_loc.alt*0.01f) < _fail_altitude_minimum)) {
// disable avoidance when close to ground, report only
action = MAV_COLLISION_ACTION_REPORT;
}
@ -617,7 +617,7 @@ bool AP_Avoidance::get_vector_perpendicular(const AP_Avoidance::Obstacle *obstac @@ -617,7 +617,7 @@ bool AP_Avoidance::get_vector_perpendicular(const AP_Avoidance::Obstacle *obstac
}
Location my_abs_pos;
if (!AP::ahrs().get_position(my_abs_pos)) {
if (!AP::ahrs().get_location(my_abs_pos)) {
// we should not get to here! If we don't know our position
// we can't know if there are any threats, for starters!
return false;

Loading…
Cancel
Save