mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AC_Circle: remove _rangefinder_use parameter
We will reuse the WPNAV_RFND_USE parameter indirectly
This commit is contained in:
parent
f3e2b182a1
commit
03441f2250
@ -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
|
||||
|
@ -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…
Reference in New Issue
Block a user