AP_Common: make Location.cpp compile without AP::ahrs() available

This commit is contained in:
Peter Barker 2023-09-25 16:18:31 +10:00 committed by Andrew Tridgell
parent e59b7a5215
commit 61be71eea6
1 changed files with 20 additions and 0 deletions

View File

@ -33,6 +33,7 @@ Location::Location(int32_t latitude, int32_t longitude, int32_t alt_in_cm, AltFr
set_alt_cm(alt_in_cm, frame); set_alt_cm(alt_in_cm, frame);
} }
#if AP_AHRS_ENABLED
Location::Location(const Vector3f &ekf_offset_neu, AltFrame frame) Location::Location(const Vector3f &ekf_offset_neu, AltFrame frame)
{ {
zero(); zero();
@ -48,6 +49,7 @@ Location::Location(const Vector3f &ekf_offset_neu, AltFrame frame)
offset(ekf_offset_neu.x * 0.01, ekf_offset_neu.y * 0.01); offset(ekf_offset_neu.x * 0.01, ekf_offset_neu.y * 0.01);
} }
} }
#endif // AP_AHRS_ENABLED
void Location::set_alt_cm(int32_t alt_cm, AltFrame frame) void Location::set_alt_cm(int32_t alt_cm, AltFrame frame)
{ {
@ -141,12 +143,17 @@ bool Location::get_alt_cm(AltFrame desired_frame, int32_t &ret_alt_cm) const
alt_abs = alt; alt_abs = alt;
break; break;
case AltFrame::ABOVE_HOME: case AltFrame::ABOVE_HOME:
#if AP_AHRS_ENABLED
if (!AP::ahrs().home_is_set()) { if (!AP::ahrs().home_is_set()) {
return false; return false;
} }
alt_abs = alt + AP::ahrs().get_home().alt; alt_abs = alt + AP::ahrs().get_home().alt;
#else
return false;
#endif // AP_AHRS_ENABLED
break; break;
case AltFrame::ABOVE_ORIGIN: case AltFrame::ABOVE_ORIGIN:
#if AP_AHRS_ENABLED
{ {
// fail if we cannot get ekf origin // fail if we cannot get ekf origin
Location ekf_origin; Location ekf_origin;
@ -156,6 +163,9 @@ bool Location::get_alt_cm(AltFrame desired_frame, int32_t &ret_alt_cm) const
alt_abs = alt + ekf_origin.alt; alt_abs = alt + ekf_origin.alt;
} }
break; break;
#else
return false;
#endif // AP_AHRS_ENABLED
case AltFrame::ABOVE_TERRAIN: case AltFrame::ABOVE_TERRAIN:
alt_abs = alt + alt_terr_cm; alt_abs = alt + alt_terr_cm;
break; break;
@ -167,12 +177,17 @@ bool Location::get_alt_cm(AltFrame desired_frame, int32_t &ret_alt_cm) const
ret_alt_cm = alt_abs; ret_alt_cm = alt_abs;
return true; return true;
case AltFrame::ABOVE_HOME: case AltFrame::ABOVE_HOME:
#if AP_AHRS_ENABLED
if (!AP::ahrs().home_is_set()) { if (!AP::ahrs().home_is_set()) {
return false; return false;
} }
ret_alt_cm = alt_abs - AP::ahrs().get_home().alt; ret_alt_cm = alt_abs - AP::ahrs().get_home().alt;
#else
return false;
#endif // AP_AHRS_ENABLED
return true; return true;
case AltFrame::ABOVE_ORIGIN: case AltFrame::ABOVE_ORIGIN:
#if AP_AHRS_ENABLED
{ {
// fail if we cannot get ekf origin // fail if we cannot get ekf origin
Location ekf_origin; Location ekf_origin;
@ -182,6 +197,9 @@ bool Location::get_alt_cm(AltFrame desired_frame, int32_t &ret_alt_cm) const
ret_alt_cm = alt_abs - ekf_origin.alt; ret_alt_cm = alt_abs - ekf_origin.alt;
return true; return true;
} }
#else
return false;
#endif // AP_AHRS_ENABLED
case AltFrame::ABOVE_TERRAIN: case AltFrame::ABOVE_TERRAIN:
ret_alt_cm = alt_abs - alt_terr_cm; ret_alt_cm = alt_abs - alt_terr_cm;
return true; return true;
@ -189,6 +207,7 @@ bool Location::get_alt_cm(AltFrame desired_frame, int32_t &ret_alt_cm) const
return false; // LCOV_EXCL_LINE - not reachable return false; // LCOV_EXCL_LINE - not reachable
} }
#if AP_AHRS_ENABLED
bool Location::get_vector_xy_from_origin_NE(Vector2f &vec_ne) const bool Location::get_vector_xy_from_origin_NE(Vector2f &vec_ne) const
{ {
Location ekf_origin; Location ekf_origin;
@ -216,6 +235,7 @@ bool Location::get_vector_from_origin_NEU(Vector3f &vec_neu) const
return true; return true;
} }
#endif // AP_AHRS_ENABLED
// return horizontal distance in meters between two locations // return horizontal distance in meters between two locations
ftype Location::get_distance(const Location &loc2) const ftype Location::get_distance(const Location &loc2) const