Browse Source

AC_Circle: remove _rangefinder_use parameter

We will reuse the WPNAV_RFND_USE parameter indirectly
c415-sdk
Randy Mackay 5 years ago
parent
commit
03441f2250
  1. 2
      libraries/AC_WPNav/AC_Circle.cpp
  2. 1
      libraries/AC_WPNav/AC_Circle.h

2
libraries/AC_WPNav/AC_Circle.cpp

@ -312,7 +312,7 @@ void AC_Circle::init_start_angle(bool use_heading) @@ -312,7 +312,7 @@ void AC_Circle::init_start_angle(bool use_heading)
AC_Circle::TerrainSource AC_Circle::get_terrain_source() const
{
// use range finder if connected
if (_rangefinder_available && _rangefinder_use) {
if (_rangefinder_available) {
return AC_Circle::TerrainSource::TERRAIN_FROM_RANGEFINDER;
}
#if AP_TERRAIN_AVAILABLE

1
libraries/AC_WPNav/AC_Circle.h

@ -140,7 +140,6 @@ private: @@ -140,7 +140,6 @@ private:
// terrain following variables
bool _terrain_alt; // true if _center.z is alt-above-terrain, false if alt-above-ekf-origin
bool _rangefinder_available; // true if range finder could be used
AP_Int8 _rangefinder_use; // true if caller has requested rangefinder be used for terrain altitude
bool _rangefinder_healthy; // true if range finder is healthy
float _rangefinder_alt_cm; // latest rangefinder altitude
};

Loading…
Cancel
Save