|
|
@ -116,13 +116,17 @@ void OpticalFlow::init(uint32_t log_bit) |
|
|
|
case OpticalFlowType::NONE: |
|
|
|
case OpticalFlowType::NONE: |
|
|
|
break; |
|
|
|
break; |
|
|
|
case OpticalFlowType::PX4FLOW: |
|
|
|
case OpticalFlowType::PX4FLOW: |
|
|
|
|
|
|
|
#if AP_OPTICALFLOW_PX4FLOW_ENABLED |
|
|
|
backend = AP_OpticalFlow_PX4Flow::detect(*this); |
|
|
|
backend = AP_OpticalFlow_PX4Flow::detect(*this); |
|
|
|
|
|
|
|
#endif |
|
|
|
break; |
|
|
|
break; |
|
|
|
case OpticalFlowType::PIXART: |
|
|
|
case OpticalFlowType::PIXART: |
|
|
|
|
|
|
|
#if AP_OPTICALFLOW_PIXART_ENABLED |
|
|
|
backend = AP_OpticalFlow_Pixart::detect("pixartflow", *this); |
|
|
|
backend = AP_OpticalFlow_Pixart::detect("pixartflow", *this); |
|
|
|
if (backend == nullptr) { |
|
|
|
if (backend == nullptr) { |
|
|
|
backend = AP_OpticalFlow_Pixart::detect("pixartPC15", *this); |
|
|
|
backend = AP_OpticalFlow_Pixart::detect("pixartPC15", *this); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
#endif |
|
|
|
break; |
|
|
|
break; |
|
|
|
case OpticalFlowType::BEBOP: |
|
|
|
case OpticalFlowType::BEBOP: |
|
|
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP |
|
|
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP |
|
|
@ -130,13 +134,17 @@ void OpticalFlow::init(uint32_t log_bit) |
|
|
|
#endif |
|
|
|
#endif |
|
|
|
break; |
|
|
|
break; |
|
|
|
case OpticalFlowType::CXOF: |
|
|
|
case OpticalFlowType::CXOF: |
|
|
|
|
|
|
|
#if AP_OPTICALFLOW_CXOF_ENABLED |
|
|
|
backend = AP_OpticalFlow_CXOF::detect(*this); |
|
|
|
backend = AP_OpticalFlow_CXOF::detect(*this); |
|
|
|
|
|
|
|
#endif |
|
|
|
break; |
|
|
|
break; |
|
|
|
case OpticalFlowType::MAVLINK: |
|
|
|
case OpticalFlowType::MAVLINK: |
|
|
|
|
|
|
|
#if AP_OPTICALFLOW_MAV_ENABLED |
|
|
|
backend = AP_OpticalFlow_MAV::detect(*this); |
|
|
|
backend = AP_OpticalFlow_MAV::detect(*this); |
|
|
|
|
|
|
|
#endif |
|
|
|
break; |
|
|
|
break; |
|
|
|
case OpticalFlowType::UAVCAN: |
|
|
|
case OpticalFlowType::UAVCAN: |
|
|
|
#if HAL_ENABLE_LIBUAVCAN_DRIVERS |
|
|
|
#if AP_OPTICALFLOW_HEREFLOW_ENABLED |
|
|
|
backend = new AP_OpticalFlow_HereFlow(*this); |
|
|
|
backend = new AP_OpticalFlow_HereFlow(*this); |
|
|
|
#endif |
|
|
|
#endif |
|
|
|
break; |
|
|
|
break; |
|
|
@ -146,7 +154,9 @@ void OpticalFlow::init(uint32_t log_bit) |
|
|
|
#endif |
|
|
|
#endif |
|
|
|
break; |
|
|
|
break; |
|
|
|
case OpticalFlowType::UPFLOW: |
|
|
|
case OpticalFlowType::UPFLOW: |
|
|
|
|
|
|
|
#if AP_OPTICALFLOW_UPFLOW_ENABLED |
|
|
|
backend = AP_OpticalFlow_UPFLOW::detect(*this); |
|
|
|
backend = AP_OpticalFlow_UPFLOW::detect(*this); |
|
|
|
|
|
|
|
#endif |
|
|
|
break; |
|
|
|
break; |
|
|
|
case OpticalFlowType::SITL: |
|
|
|
case OpticalFlowType::SITL: |
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL |
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL |
|
|
|