mirror of https://github.com/ArduPilot/ardupilot
AP_OpticalFlow: add and use AP_OpticalFlow_config.h
This commit is contained in:
parent
da36de3b80
commit
3e1388b7e6
|
@ -14,19 +14,7 @@
|
|||
*/
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef AP_OPTICALFLOW_ENABLED
|
||||
#define AP_OPTICALFLOW_ENABLED 1
|
||||
#endif
|
||||
|
||||
#ifndef HAL_MSP_OPTICALFLOW_ENABLED
|
||||
#define HAL_MSP_OPTICALFLOW_ENABLED (AP_OPTICALFLOW_ENABLED && (HAL_MSP_ENABLED && !HAL_MINIMIZE_FEATURES))
|
||||
#endif
|
||||
|
||||
#ifndef AP_OPTICALFLOW_SITL_ENABLED
|
||||
#define AP_OPTICALFLOW_SITL_ENABLED AP_SIM_ENABLED
|
||||
#endif
|
||||
#include "AP_OpticalFlow_config.h"
|
||||
|
||||
#if AP_OPTICALFLOW_ENABLED
|
||||
|
||||
|
|
|
@ -20,6 +20,8 @@
|
|||
|
||||
#include "AP_OpticalFlow.h"
|
||||
|
||||
#include <AP_HAL/Semaphores.h>
|
||||
|
||||
class OpticalFlow_backend
|
||||
{
|
||||
friend class AP_OpticalFlow;
|
||||
|
|
|
@ -1,14 +1,10 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_OpticalFlow.h"
|
||||
|
||||
#ifndef AP_OPTICALFLOW_CXOF_ENABLED
|
||||
#define AP_OPTICALFLOW_CXOF_ENABLED AP_OPTICALFLOW_ENABLED
|
||||
#endif
|
||||
#include "AP_OpticalFlow_config.h"
|
||||
|
||||
#if AP_OPTICALFLOW_CXOF_ENABLED
|
||||
|
||||
#include <AP_HAL/utility/OwnPtr.h>
|
||||
#include "AP_OpticalFlow_Backend.h"
|
||||
|
||||
class AP_OpticalFlow_CXOF : public OpticalFlow_backend
|
||||
{
|
||||
|
|
|
@ -1,13 +1,10 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_OpticalFlow.h"
|
||||
|
||||
#ifndef AP_OPTICALFLOW_HEREFLOW_ENABLED
|
||||
#define AP_OPTICALFLOW_HEREFLOW_ENABLED (AP_OPTICALFLOW_ENABLED && HAL_ENABLE_DRONECAN_DRIVERS)
|
||||
#endif
|
||||
#include "AP_OpticalFlow_config.h"
|
||||
|
||||
#if AP_OPTICALFLOW_HEREFLOW_ENABLED
|
||||
|
||||
#include "AP_OpticalFlow_Backend.h"
|
||||
#include <AP_DroneCAN/AP_DroneCAN.h>
|
||||
|
||||
class AP_OpticalFlow_HereFlow : public OpticalFlow_backend {
|
||||
|
|
|
@ -1,13 +1,10 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_OpticalFlow.h"
|
||||
|
||||
#ifndef AP_OPTICALFLOW_MAV_ENABLED
|
||||
#define AP_OPTICALFLOW_MAV_ENABLED AP_OPTICALFLOW_ENABLED
|
||||
#endif
|
||||
#include "AP_OpticalFlow_config.h"
|
||||
|
||||
#if AP_OPTICALFLOW_MAV_ENABLED
|
||||
|
||||
#include "AP_OpticalFlow_Backend.h"
|
||||
#include <AP_HAL/utility/OwnPtr.h>
|
||||
|
||||
class AP_OpticalFlow_MAV : public OpticalFlow_backend
|
||||
|
|
|
@ -12,17 +12,15 @@
|
|||
You should have received a copy of the GNU General Public License
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#include "AP_OpticalFlow_Onboard.h"
|
||||
|
||||
#include "AP_OpticalFlow_config.h"
|
||||
|
||||
#if AP_OPTICALFLOW_ONBOARD_ENABLED
|
||||
|
||||
#include "AP_OpticalFlow_Onboard.h"
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#include "AP_OpticalFlow.h"
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX &&\
|
||||
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
|
||||
|
||||
#ifndef OPTICALFLOW_ONBOARD_DEBUG
|
||||
#define OPTICALFLOW_ONBOARD_DEBUG 0
|
||||
#endif
|
||||
|
@ -95,6 +93,4 @@ void AP_OpticalFlow_Onboard::update()
|
|||
#endif
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
#endif // AP_OPTICALFLOW_ONBOARD_ENABLED
|
||||
|
|
|
@ -14,18 +14,11 @@
|
|||
*/
|
||||
#pragma once
|
||||
|
||||
#include <AP_OpticalFlow/AP_OpticalFlow.h>
|
||||
|
||||
#ifndef AP_OPTICALFLOW_ONBOARD_ENABLED
|
||||
#define AP_OPTICALFLOW_ONBOARD_ENABLED AP_OPTICALFLOW_ENABLED
|
||||
#endif
|
||||
#include "AP_OpticalFlow_config.h"
|
||||
|
||||
#if AP_OPTICALFLOW_ONBOARD_ENABLED
|
||||
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_NavEKF2/AP_NavEKF2.h>
|
||||
#include <AP_NavEKF3/AP_NavEKF3.h>
|
||||
#include <AP_OpticalFlow/AP_OpticalFlow_Backend.h>
|
||||
|
||||
#include "AP_OpticalFlow.h"
|
||||
|
||||
|
|
|
@ -16,10 +16,12 @@
|
|||
driver for PX4Flow optical flow sensor
|
||||
*/
|
||||
|
||||
#include "AP_OpticalFlow_PX4Flow.h"
|
||||
#include "AP_OpticalFlow_config.h"
|
||||
|
||||
#if AP_OPTICALFLOW_PX4FLOW_ENABLED
|
||||
|
||||
#include "AP_OpticalFlow_PX4Flow.h"
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Math/crc.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
|
|
@ -1,13 +1,10 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_OpticalFlow.h"
|
||||
|
||||
#ifndef AP_OPTICALFLOW_PX4FLOW_ENABLED
|
||||
#define AP_OPTICALFLOW_PX4FLOW_ENABLED AP_OPTICALFLOW_ENABLED
|
||||
#endif
|
||||
#include "AP_OpticalFlow_config.h"
|
||||
|
||||
#if AP_OPTICALFLOW_PX4FLOW_ENABLED
|
||||
|
||||
#include "AP_OpticalFlow_Backend.h"
|
||||
#include <AP_HAL/utility/OwnPtr.h>
|
||||
|
||||
class AP_OpticalFlow_PX4Flow : public OpticalFlow_backend
|
||||
|
|
|
@ -20,10 +20,12 @@
|
|||
timing for register reads and writes is critical
|
||||
*/
|
||||
|
||||
#include "AP_OpticalFlow_Pixart.h"
|
||||
#include "AP_OpticalFlow_config.h"
|
||||
|
||||
#if AP_OPTICALFLOW_PIXART_ENABLED
|
||||
|
||||
#include "AP_OpticalFlow_Pixart.h"
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Math/crc.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
|
|
@ -1,13 +1,11 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_OpticalFlow.h"
|
||||
|
||||
#ifndef AP_OPTICALFLOW_PIXART_ENABLED
|
||||
#define AP_OPTICALFLOW_PIXART_ENABLED AP_OPTICALFLOW_ENABLED
|
||||
#endif
|
||||
#include "AP_OpticalFlow_config.h"
|
||||
|
||||
#if AP_OPTICALFLOW_PIXART_ENABLED
|
||||
|
||||
#include "AP_OpticalFlow_Backend.h"
|
||||
|
||||
#include <AP_HAL/utility/OwnPtr.h>
|
||||
|
||||
class AP_OpticalFlow_Pixart : public OpticalFlow_backend
|
||||
|
|
|
@ -1,9 +1,11 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_OpticalFlow.h"
|
||||
#include "AP_OpticalFlow_config.h"
|
||||
|
||||
#if AP_OPTICALFLOW_SITL_ENABLED
|
||||
|
||||
#include "AP_OpticalFlow.h"
|
||||
|
||||
class AP_OpticalFlow_SITL : public OpticalFlow_backend
|
||||
{
|
||||
public:
|
||||
|
|
|
@ -1,13 +1,10 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_OpticalFlow.h"
|
||||
|
||||
#ifndef AP_OPTICALFLOW_UPFLOW_ENABLED
|
||||
#define AP_OPTICALFLOW_UPFLOW_ENABLED AP_OPTICALFLOW_ENABLED
|
||||
#endif
|
||||
#include "AP_OpticalFlow_config.h"
|
||||
|
||||
#if AP_OPTICALFLOW_UPFLOW_ENABLED
|
||||
|
||||
#include "AP_OpticalFlow_Backend.h"
|
||||
#include <AP_HAL/utility/OwnPtr.h>
|
||||
|
||||
class AP_OpticalFlow_UPFLOW : public OpticalFlow_backend
|
||||
|
|
|
@ -0,0 +1,49 @@
|
|||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
#include <AP_MSP/AP_MSP_config.h>
|
||||
#include <GCS_MAVLink/GCS_config.h>
|
||||
|
||||
#ifndef AP_OPTICALFLOW_ENABLED
|
||||
#define AP_OPTICALFLOW_ENABLED 1
|
||||
#endif
|
||||
|
||||
#ifndef AP_OPTICALFLOW_BACKEND_DEFAULT_ENABLED
|
||||
#define AP_OPTICALFLOW_BACKEND_DEFAULT_ENABLED AP_OPTICALFLOW_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_OPTICALFLOW_CXOF_ENABLED
|
||||
#define AP_OPTICALFLOW_CXOF_ENABLED AP_OPTICALFLOW_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_OPTICALFLOW_HEREFLOW_ENABLED
|
||||
#define AP_OPTICALFLOW_HEREFLOW_ENABLED (AP_OPTICALFLOW_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_DRONECAN_DRIVERS)
|
||||
#endif
|
||||
|
||||
#ifndef AP_OPTICALFLOW_MAV_ENABLED
|
||||
#define AP_OPTICALFLOW_MAV_ENABLED (AP_OPTICALFLOW_BACKEND_DEFAULT_ENABLED && HAL_GCS_ENABLED)
|
||||
#endif
|
||||
|
||||
#ifndef HAL_MSP_OPTICALFLOW_ENABLED
|
||||
#define HAL_MSP_OPTICALFLOW_ENABLED (AP_OPTICALFLOW_BACKEND_DEFAULT_ENABLED && (HAL_MSP_ENABLED && !HAL_MINIMIZE_FEATURES))
|
||||
#endif
|
||||
|
||||
#ifndef AP_OPTICALFLOW_ONBOARD_ENABLED
|
||||
#define AP_OPTICALFLOW_ONBOARD_ENABLED (AP_OPTICALFLOW_BACKEND_DEFAULT_ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_LINUX && CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP)
|
||||
#endif
|
||||
|
||||
#ifndef AP_OPTICALFLOW_PIXART_ENABLED
|
||||
#define AP_OPTICALFLOW_PIXART_ENABLED AP_OPTICALFLOW_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_OPTICALFLOW_PX4FLOW_ENABLED
|
||||
#define AP_OPTICALFLOW_PX4FLOW_ENABLED AP_OPTICALFLOW_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_OPTICALFLOW_SITL_ENABLED
|
||||
#define AP_OPTICALFLOW_SITL_ENABLED (AP_OPTICALFLOW_BACKEND_DEFAULT_ENABLED && AP_SIM_ENABLED)
|
||||
#endif
|
||||
|
||||
#ifndef AP_OPTICALFLOW_UPFLOW_ENABLED
|
||||
#define AP_OPTICALFLOW_UPFLOW_ENABLED AP_OPTICALFLOW_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
Loading…
Reference in New Issue