Skip to content

Commit 088d1f3

Browse files
committed
Copter: minor change to get_rangefinder_height_interpolated
1 parent 20ee529 commit 088d1f3

File tree

2 files changed

+2
-2
lines changed

2 files changed

+2
-2
lines changed

ArduCopter/Copter.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -260,7 +260,7 @@ class Copter : public AP_Vehicle {
260260
AP_SurfaceDistance rangefinder_up_state {ROTATION_PITCH_90, inertial_nav, 1U};
261261

262262
// helper function to get inertially interpolated rangefinder height.
263-
bool get_rangefinder_height_interpolated_cm(int32_t& ret) const;
263+
bool get_rangefinder_height_interpolated_cm(int32_t& ret);
264264

265265
#if AP_RANGEFINDER_ENABLED
266266
class SurfaceTracking {

ArduCopter/sensors.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -68,7 +68,7 @@ void Copter::update_rangefinder_terrain_offset()
6868
}
6969

7070
// helper function to get inertially interpolated rangefinder height.
71-
bool Copter::get_rangefinder_height_interpolated_cm(int32_t& ret) const
71+
bool Copter::get_rangefinder_height_interpolated_cm(int32_t& ret)
7272
{
7373
#if AP_RANGEFINDER_ENABLED
7474
return rangefinder_state.get_rangefinder_height_interpolated_cm(ret);

0 commit comments

Comments
 (0)