mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: get_rangefinder_height_interpolated_cm made const
This commit is contained in:
parent
94064175af
commit
46023318d4
@ -255,10 +255,8 @@ private:
|
|||||||
uint32_t glitch_cleared_ms; // system time glitch cleared
|
uint32_t glitch_cleared_ms; // system time glitch cleared
|
||||||
} rangefinder_state, rangefinder_up_state;
|
} rangefinder_state, rangefinder_up_state;
|
||||||
|
|
||||||
/*
|
// return rangefinder height interpolated using inertial altitude
|
||||||
return rangefinder height interpolated using inertial altitude
|
bool get_rangefinder_height_interpolated_cm(int32_t& ret) const;
|
||||||
*/
|
|
||||||
bool get_rangefinder_height_interpolated_cm(int32_t& ret);
|
|
||||||
|
|
||||||
class SurfaceTracking {
|
class SurfaceTracking {
|
||||||
public:
|
public:
|
||||||
|
@ -135,7 +135,7 @@ bool Copter::rangefinder_up_ok() const
|
|||||||
difference between the inertial height at that time and the current
|
difference between the inertial height at that time and the current
|
||||||
inertial height to give us interpolation of height from rangefinder
|
inertial height to give us interpolation of height from rangefinder
|
||||||
*/
|
*/
|
||||||
bool Copter::get_rangefinder_height_interpolated_cm(int32_t& ret)
|
bool Copter::get_rangefinder_height_interpolated_cm(int32_t& ret) const
|
||||||
{
|
{
|
||||||
if (!rangefinder_alt_ok()) {
|
if (!rangefinder_alt_ok()) {
|
||||||
return false;
|
return false;
|
||||||
|
Loading…
Reference in New Issue
Block a user