mirror of https://github.com/ArduPilot/ardupilot
ArduPlane: rename AP_AHRS::get_position to get_location
This commit is contained in:
parent
d1acc5df31
commit
266d384ca7
|
@ -396,7 +396,7 @@ void Plane::update_GPS_50Hz(void)
|
||||||
gps.update();
|
gps.update();
|
||||||
|
|
||||||
// get position from AHRS
|
// get position from AHRS
|
||||||
have_position = ahrs.get_position(current_loc);
|
have_position = ahrs.get_location(current_loc);
|
||||||
ahrs.get_relative_position_D_home(relative_altitude);
|
ahrs.get_relative_position_D_home(relative_altitude);
|
||||||
relative_altitude *= -1.0f;
|
relative_altitude *= -1.0f;
|
||||||
}
|
}
|
||||||
|
|
|
@ -1340,7 +1340,7 @@ int16_t GCS_MAVLINK_Plane::high_latency_target_altitude() const
|
||||||
{
|
{
|
||||||
AP_AHRS &ahrs = AP::ahrs();
|
AP_AHRS &ahrs = AP::ahrs();
|
||||||
struct Location global_position_current;
|
struct Location global_position_current;
|
||||||
UNUSED_RESULT(ahrs.get_position(global_position_current));
|
UNUSED_RESULT(ahrs.get_location(global_position_current));
|
||||||
|
|
||||||
#if HAL_QUADPLANE_ENABLED
|
#if HAL_QUADPLANE_ENABLED
|
||||||
const QuadPlane &quadplane = plane.quadplane;
|
const QuadPlane &quadplane = plane.quadplane;
|
||||||
|
|
|
@ -122,7 +122,7 @@ void Plane::update_home()
|
||||||
}
|
}
|
||||||
if (ahrs.home_is_set() && !ahrs.home_is_locked()) {
|
if (ahrs.home_is_set() && !ahrs.home_is_locked()) {
|
||||||
Location loc;
|
Location loc;
|
||||||
if(ahrs.get_position(loc) && gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
|
if(ahrs.get_location(loc) && gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
|
||||||
// we take the altitude directly from the GPS as we are
|
// we take the altitude directly from the GPS as we are
|
||||||
// about to reset the baro calibration. We can't use AHRS
|
// about to reset the baro calibration. We can't use AHRS
|
||||||
// altitude or we can end up perpetuating a bias in
|
// altitude or we can end up perpetuating a bias in
|
||||||
|
|
|
@ -2542,7 +2542,7 @@ void QuadPlane::vtol_position_controller(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (plane.control_mode == &plane.mode_guided || vtol_loiter_auto) {
|
if (plane.control_mode == &plane.mode_guided || vtol_loiter_auto) {
|
||||||
plane.ahrs.get_position(plane.current_loc);
|
plane.ahrs.get_location(plane.current_loc);
|
||||||
int32_t target_altitude_cm;
|
int32_t target_altitude_cm;
|
||||||
if (!plane.next_WP_loc.get_alt_cm(Location::AltFrame::ABOVE_HOME,target_altitude_cm)) {
|
if (!plane.next_WP_loc.get_alt_cm(Location::AltFrame::ABOVE_HOME,target_altitude_cm)) {
|
||||||
break;
|
break;
|
||||||
|
|
Loading…
Reference in New Issue