mirror of https://github.com/ArduPilot/ardupilot
Sub: Fix rangefinder init
This commit is contained in:
parent
d28f9151c5
commit
698e4e440e
|
@ -178,7 +178,7 @@ private:
|
|||
Compass compass;
|
||||
AP_InertialSensor ins;
|
||||
|
||||
RangeFinder rangefinder{serial_manager, ROTATION_PITCH_270};
|
||||
RangeFinder rangefinder{serial_manager};
|
||||
struct {
|
||||
bool enabled:1;
|
||||
bool alt_healthy:1; // true if we can trust the altitude from the rangefinder
|
||||
|
|
|
@ -13,7 +13,7 @@ void Sub::read_barometer()
|
|||
void Sub::init_rangefinder()
|
||||
{
|
||||
#if RANGEFINDER_ENABLED == ENABLED
|
||||
rangefinder.init();
|
||||
rangefinder.init(ROTATION_PITCH_270);
|
||||
rangefinder_state.alt_cm_filt.set_cutoff_frequency(RANGEFINDER_WPNAV_FILT_HZ);
|
||||
rangefinder_state.enabled = rangefinder.has_orientation(ROTATION_PITCH_270);
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue