Skip to content

Commit 3caf7b4

Browse files
committed
AP_Common: add get_alt - 100 times better than get_alt_cm
1 parent 3ebb62a commit 3caf7b4

File tree

2 files changed

+11
-0
lines changed

2 files changed

+11
-0
lines changed

libraries/AP_Common/Location.cpp

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -209,6 +209,15 @@ bool Location::get_alt_cm(AltFrame desired_frame, int32_t &ret_alt_cm) const
209209
}
210210
return false; // LCOV_EXCL_LINE - not reachable
211211
}
212+
bool Location::get_alt(AltFrame desired_frame, float &ret_alt) const
213+
{
214+
int32_t ret_alt_cm;
215+
if (!get_alt_cm(desired_frame, ret_alt_cm)) {
216+
return false;
217+
}
218+
ret_alt = ret_alt_cm * 0.01;
219+
return true;
220+
}
212221

213222
#if AP_AHRS_ENABLED
214223
bool Location::get_vector_xy_from_origin_NE(Vector2f &vec_ne) const

libraries/AP_Common/Location.h

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -42,6 +42,8 @@ class Location
4242
// - above-home and home is not set
4343
// - above-origin and origin is not set
4444
bool get_alt_cm(AltFrame desired_frame, int32_t &ret_alt_cm) const WARN_IF_UNUSED;
45+
// same as get_alt_cm but in metres:
46+
bool get_alt(AltFrame desired_frame, float &ret_alt) const WARN_IF_UNUSED;
4547

4648
// get altitude frame
4749
AltFrame get_alt_frame() const;

0 commit comments

Comments
 (0)