diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Bebop.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Bebop.cpp index d95f92edb7..8e1d3dfed5 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Bebop.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Bebop.cpp @@ -62,8 +62,8 @@ static const uint16_t waveform_mode1[32] = { 1675, 1540, 1492, 1374, 1292 }; -AP_RangeFinder_Bebop::AP_RangeFinder_Bebop(RangeFinder::RangeFinder_State &_state) : - AP_RangeFinder_Backend(_state), +AP_RangeFinder_Bebop::AP_RangeFinder_Bebop(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) : + AP_RangeFinder_Backend(_state, _params), _thread(new Linux::Thread(FUNCTOR_BIND_MEMBER(&AP_RangeFinder_Bebop::_loop, void))) { _init(); diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Bebop.h b/libraries/AP_RangeFinder/AP_RangeFinder_Bebop.h index ec3cd451f4..b053cd7e32 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Bebop.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Bebop.h @@ -88,7 +88,7 @@ struct adc_capture { class AP_RangeFinder_Bebop : public AP_RangeFinder_Backend { public: - AP_RangeFinder_Bebop(RangeFinder::RangeFinder_State &_state); + AP_RangeFinder_Bebop(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params); ~AP_RangeFinder_Bebop(void); static bool detect(); diff --git a/libraries/AP_RangeFinder/RangeFinder.cpp b/libraries/AP_RangeFinder/RangeFinder.cpp index 5d49cfed80..62832816cf 100644 --- a/libraries/AP_RangeFinder/RangeFinder.cpp +++ b/libraries/AP_RangeFinder/RangeFinder.cpp @@ -458,7 +458,7 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO) && defined(HAVE_LIBIIO) case RangeFinder_TYPE_BEBOP: if (AP_RangeFinder_Bebop::detect()) { - drivers[instance] = new AP_RangeFinder_Bebop(state[instance]); + drivers[instance] = new AP_RangeFinder_Bebop(state[instance], params[instance]); } break; #endif