|
|
|
@ -104,9 +104,6 @@ void OpticalFlow::init(uint32_t log_bit)
@@ -104,9 +104,6 @@ void OpticalFlow::init(uint32_t log_bit)
|
|
|
|
|
if (backend == nullptr) { |
|
|
|
|
backend = AP_OpticalFlow_PX4Flow::detect(*this); |
|
|
|
|
} |
|
|
|
|
if (backend == nullptr) { |
|
|
|
|
backend = AP_OpticalFlow_CXOF::detect(*this); |
|
|
|
|
} |
|
|
|
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL |
|
|
|
|
backend = new AP_OpticalFlow_SITL(*this); |
|
|
|
|
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP |
|
|
|
@ -118,6 +115,9 @@ void OpticalFlow::init(uint32_t log_bit)
@@ -118,6 +115,9 @@ void OpticalFlow::init(uint32_t log_bit)
|
|
|
|
|
#elif defined(HAL_HAVE_PIXARTFLOW_SPI) |
|
|
|
|
backend = AP_OpticalFlow_Pixart::detect("pixartflow", *this); |
|
|
|
|
#endif |
|
|
|
|
if (backend == nullptr) { |
|
|
|
|
backend = AP_OpticalFlow_CXOF::detect(*this); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (backend != nullptr) { |
|
|
|
|