@ -222,7 +222,7 @@ private:
AP_InertialSensor ins;
RangeFinder rangefinder{serial_manager, ROTATION_PITCH_270};
RangeFinder rangefinder{serial_manager};
AP_Vehicle::FixedWing::Rangefinder_State rangefinder_state;
@ -87,7 +87,7 @@ void Plane::init_ardupilot()
barometer.init();
// initialise rangefinder
rangefinder.init();
rangefinder.init(ROTATION_PITCH_270);
// initialise battery monitoring
battery.init();