AP_Common: add get_alt - 100 times better than get_alt_cm
This commit is contained in:
parent
423198cef0
commit
44359ff6b2
@ -209,6 +209,15 @@ bool Location::get_alt_cm(AltFrame desired_frame, int32_t &ret_alt_cm) const
|
||||
}
|
||||
return false; // LCOV_EXCL_LINE - not reachable
|
||||
}
|
||||
bool Location::get_alt_m(AltFrame desired_frame, float &ret_alt) const
|
||||
{
|
||||
int32_t ret_alt_cm;
|
||||
if (!get_alt_cm(desired_frame, ret_alt_cm)) {
|
||||
return false;
|
||||
}
|
||||
ret_alt = ret_alt_cm * 0.01;
|
||||
return true;
|
||||
}
|
||||
|
||||
#if AP_AHRS_ENABLED
|
||||
bool Location::get_vector_xy_from_origin_NE(Vector2f &vec_ne) const
|
||||
|
@ -42,6 +42,8 @@ public:
|
||||
// - above-home and home is not set
|
||||
// - above-origin and origin is not set
|
||||
bool get_alt_cm(AltFrame desired_frame, int32_t &ret_alt_cm) const WARN_IF_UNUSED;
|
||||
// same as get_alt_cm but in metres:
|
||||
bool get_alt_m(AltFrame desired_frame, float &ret_alt) const WARN_IF_UNUSED;
|
||||
|
||||
// get altitude frame
|
||||
AltFrame get_alt_frame() const;
|
||||
|
Loading…
Reference in New Issue
Block a user