mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Copter: Fix RangeFinder init
This commit is contained in:
parent
8cf7c47f96
commit
d1246f5868
@ -237,7 +237,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 Copter::read_barometer(void)
|
||||
void Copter::init_rangefinder(void)
|
||||
{
|
||||
#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
Block a user