mirror of https://github.com/ArduPilot/ardupilot
AP_RangeFinder: move remaining feature defines into _config.h
This commit is contained in:
parent
d5dd4151eb
commit
bf3bafcd17
|
@ -41,10 +41,6 @@
|
|||
#define RANGEFINDER_PREARM_REQUIRED_CHANGE_CM 50
|
||||
#endif
|
||||
|
||||
#ifndef HAL_MSP_RANGEFINDER_ENABLED
|
||||
#define HAL_MSP_RANGEFINDER_ENABLED HAL_MSP_ENABLED
|
||||
#endif
|
||||
|
||||
class AP_RangeFinder_Backend;
|
||||
|
||||
class RangeFinder
|
||||
|
|
|
@ -1,14 +1,11 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_RangeFinder.h"
|
||||
|
||||
#ifndef AP_RANGEFINDER_BENEWAKE_ENABLED
|
||||
#define AP_RANGEFINDER_BENEWAKE_ENABLED AP_RANGEFINDER_ENABLED
|
||||
#endif
|
||||
#include "AP_RangeFinder_config.h"
|
||||
|
||||
#if AP_RANGEFINDER_BENEWAKE_ENABLED
|
||||
|
||||
#include "AP_RangeFinder_Backend_Serial.h"
|
||||
#include "AP_RangeFinder.h"
|
||||
|
||||
class AP_RangeFinder_Benewake : public AP_RangeFinder_Backend_Serial
|
||||
{
|
||||
|
|
|
@ -1,15 +1,12 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_RangeFinder_Backend.h"
|
||||
|
||||
#include <AP_CANManager/AP_CANSensor.h>
|
||||
|
||||
#ifndef AP_RANGEFINDER_BENEWAKE_CAN_ENABLED
|
||||
#define AP_RANGEFINDER_BENEWAKE_CAN_ENABLED (HAL_MAX_CAN_PROTOCOL_DRIVERS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED)
|
||||
#endif
|
||||
#include "AP_RangeFinder_config.h"
|
||||
|
||||
#if AP_RANGEFINDER_BENEWAKE_CAN_ENABLED
|
||||
|
||||
#include "AP_RangeFinder_Backend.h"
|
||||
#include <AP_CANManager/AP_CANSensor.h>
|
||||
|
||||
class Benewake_MultiCAN;
|
||||
|
||||
class AP_RangeFinder_Benewake_CAN : public AP_RangeFinder_Backend {
|
||||
|
|
|
@ -1,13 +1,11 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_RangeFinder_Benewake.h"
|
||||
|
||||
#ifndef AP_RANGEFINDER_BENEWAKE_TF02_ENABLED
|
||||
#define AP_RANGEFINDER_BENEWAKE_TF02_ENABLED (AP_RANGEFINDER_BENEWAKE_ENABLED && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED)
|
||||
#endif
|
||||
#include "AP_RangeFinder_config.h"
|
||||
|
||||
#if AP_RANGEFINDER_BENEWAKE_TF02_ENABLED
|
||||
|
||||
#include "AP_RangeFinder_Benewake.h"
|
||||
|
||||
class AP_RangeFinder_Benewake_TF02 : public AP_RangeFinder_Benewake
|
||||
{
|
||||
public:
|
||||
|
|
|
@ -1,13 +1,11 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_RangeFinder_Benewake.h"
|
||||
|
||||
#ifndef AP_RANGEFINDER_BENEWAKE_TF03_ENABLED
|
||||
#define AP_RANGEFINDER_BENEWAKE_TF03_ENABLED (AP_RANGEFINDER_BENEWAKE_ENABLED && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED)
|
||||
#endif
|
||||
#include "AP_RangeFinder_config.h"
|
||||
|
||||
#if AP_RANGEFINDER_BENEWAKE_TF03_ENABLED
|
||||
|
||||
#include "AP_RangeFinder_Benewake.h"
|
||||
|
||||
class AP_RangeFinder_Benewake_TF03 : public AP_RangeFinder_Benewake
|
||||
{
|
||||
public:
|
||||
|
|
|
@ -1,13 +1,11 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_RangeFinder_Benewake.h"
|
||||
|
||||
#ifndef AP_RANGEFINDER_BENEWAKE_TFMINI_ENABLED
|
||||
#define AP_RANGEFINDER_BENEWAKE_TFMINI_ENABLED (AP_RANGEFINDER_BENEWAKE_ENABLED && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED)
|
||||
#endif
|
||||
#include "AP_RangeFinder_config.h"
|
||||
|
||||
#if AP_RANGEFINDER_BENEWAKE_TFMINI_ENABLED
|
||||
|
||||
#include "AP_RangeFinder_Benewake.h"
|
||||
|
||||
class AP_RangeFinder_Benewake_TFMini : public AP_RangeFinder_Benewake
|
||||
{
|
||||
public:
|
||||
|
|
|
@ -16,15 +16,13 @@
|
|||
*/
|
||||
#pragma once
|
||||
|
||||
#include "AP_RangeFinder.h"
|
||||
#include "AP_RangeFinder_Backend.h"
|
||||
|
||||
#ifndef AP_RANGEFINDER_BENEWAKE_TFMINIPLUS_ENABLED
|
||||
#define AP_RANGEFINDER_BENEWAKE_TFMINIPLUS_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
#include "AP_RangeFinder_config.h"
|
||||
|
||||
#if AP_RANGEFINDER_BENEWAKE_TFMINIPLUS_ENABLED
|
||||
|
||||
#include "AP_RangeFinder.h"
|
||||
#include "AP_RangeFinder_Backend.h"
|
||||
|
||||
#define TFMINIPLUS_ADDR_DEFAULT 0x10 // TFMini default device id
|
||||
|
||||
#include <AP_HAL/utility/sparse-endian.h>
|
||||
|
|
|
@ -1,13 +1,10 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_RangeFinder_Backend.h"
|
||||
|
||||
#ifndef AP_RANGEFINDER_DRONECAN_ENABLED
|
||||
#define AP_RANGEFINDER_DRONECAN_ENABLED (HAL_ENABLE_DRONECAN_DRIVERS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED)
|
||||
#endif
|
||||
#include "AP_RangeFinder_config.h"
|
||||
|
||||
#if AP_RANGEFINDER_DRONECAN_ENABLED
|
||||
|
||||
#include "AP_RangeFinder_Backend.h"
|
||||
#include <AP_DroneCAN/AP_DroneCAN.h>
|
||||
|
||||
class MeasurementCb;
|
||||
|
|
|
@ -1,13 +1,10 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_RangeFinder.h"
|
||||
|
||||
#ifndef AP_RANGEFINDER_GYUS42V2_ENABLED
|
||||
#define AP_RANGEFINDER_GYUS42V2_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
#include "AP_RangeFinder_config.h"
|
||||
|
||||
#if AP_RANGEFINDER_GYUS42V2_ENABLED
|
||||
|
||||
#include "AP_RangeFinder.h"
|
||||
#include "AP_RangeFinder_Backend_Serial.h"
|
||||
|
||||
class AP_RangeFinder_GYUS42v2 : public AP_RangeFinder_Backend_Serial
|
||||
|
|
|
@ -1,14 +1,12 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_RangeFinder_config.h"
|
||||
|
||||
#if AP_RANGEFINDER_HC_SR04_ENABLED
|
||||
|
||||
#include "AP_RangeFinder.h"
|
||||
#include "AP_RangeFinder_Backend.h"
|
||||
|
||||
#ifndef AP_RANGEFINDER_HC_SR04_ENABLED
|
||||
#define AP_RANGEFINDER_HC_SR04_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#if AP_RANGEFINDER_HC_SR04_ENABLED
|
||||
|
||||
#include "AP_RangeFinder_Params.h"
|
||||
|
||||
class AP_RangeFinder_HC_SR04 : public AP_RangeFinder_Backend
|
||||
|
|
|
@ -1,14 +1,12 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_RangeFinder_config.h"
|
||||
|
||||
#if AP_RANGEFINDER_LANBAO_ENABLED
|
||||
|
||||
#include "AP_RangeFinder.h"
|
||||
#include "AP_RangeFinder_Backend_Serial.h"
|
||||
|
||||
#ifndef AP_RANGEFINDER_LANBAO_ENABLED
|
||||
#define AP_RANGEFINDER_LANBAO_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#if AP_RANGEFINDER_LANBAO_ENABLED
|
||||
|
||||
class AP_RangeFinder_Lanbao : public AP_RangeFinder_Backend_Serial
|
||||
{
|
||||
|
||||
|
|
|
@ -1,14 +1,12 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_RangeFinder_config.h"
|
||||
|
||||
#if AP_RANGEFINDER_LEDDARONE_ENABLED
|
||||
|
||||
#include "AP_RangeFinder.h"
|
||||
#include "AP_RangeFinder_Backend_Serial.h"
|
||||
|
||||
#ifndef AP_RANGEFINDER_LEDDARONE_ENABLED
|
||||
#define AP_RANGEFINDER_LEDDARONE_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#if AP_RANGEFINDER_LEDDARONE_ENABLED
|
||||
|
||||
// defines
|
||||
#define LEDDARONE_DEFAULT_ADDRESS 0x01
|
||||
#define LEDDARONE_MODOBUS_FUNCTION_CODE 0x04
|
||||
|
|
|
@ -1,14 +1,12 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_RangeFinder_config.h"
|
||||
|
||||
#if AP_RANGEFINDER_LEDDARVU8_ENABLED
|
||||
|
||||
#include "AP_RangeFinder.h"
|
||||
#include "AP_RangeFinder_Backend_Serial.h"
|
||||
|
||||
#ifndef AP_RANGEFINDER_LEDDARVU8_ENABLED
|
||||
#define AP_RANGEFINDER_LEDDARVU8_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#if AP_RANGEFINDER_LEDDARVU8_ENABLED
|
||||
|
||||
#define LEDDARVU8_PAYLOAD_LENGTH (8*2)
|
||||
|
||||
class AP_RangeFinder_LeddarVu8 : public AP_RangeFinder_Backend_Serial
|
||||
|
|
|
@ -1,14 +1,12 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_RangeFinder_config.h"
|
||||
|
||||
#if AP_RANGEFINDER_LWI2C_ENABLED
|
||||
|
||||
#include "AP_RangeFinder.h"
|
||||
#include "AP_RangeFinder_Backend.h"
|
||||
|
||||
#ifndef AP_RANGEFINDER_LWI2C_ENABLED
|
||||
#define AP_RANGEFINDER_LWI2C_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#if AP_RANGEFINDER_LWI2C_ENABLED
|
||||
|
||||
#include <AP_HAL/I2CDevice.h>
|
||||
|
||||
#define NUM_SF20_DATA_STREAMS 1
|
||||
|
|
|
@ -1,14 +1,12 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_RangeFinder_config.h"
|
||||
|
||||
#if AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED
|
||||
|
||||
#include "AP_RangeFinder.h"
|
||||
#include "AP_RangeFinder_Backend_Serial.h"
|
||||
|
||||
#ifndef AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED
|
||||
#define AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#if AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED
|
||||
|
||||
class AP_RangeFinder_LightWareSerial : public AP_RangeFinder_Backend_Serial
|
||||
{
|
||||
|
||||
|
|
|
@ -1,14 +1,12 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_RangeFinder_config.h"
|
||||
|
||||
#if AP_RANGEFINDER_MAVLINK_ENABLED
|
||||
|
||||
#include "AP_RangeFinder.h"
|
||||
#include "AP_RangeFinder_Backend.h"
|
||||
|
||||
#ifndef AP_RANGEFINDER_MAVLINK_ENABLED
|
||||
#define AP_RANGEFINDER_MAVLINK_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#if AP_RANGEFINDER_MAVLINK_ENABLED
|
||||
|
||||
// Data timeout
|
||||
#define AP_RANGEFINDER_MAVLINK_TIMEOUT_MS 500
|
||||
|
||||
|
|
|
@ -1,10 +1,12 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_RangeFinder_config.h"
|
||||
|
||||
#if HAL_MSP_RANGEFINDER_ENABLED
|
||||
|
||||
#include "AP_RangeFinder.h"
|
||||
#include "AP_RangeFinder_Backend.h"
|
||||
|
||||
#if HAL_MSP_RANGEFINDER_ENABLED
|
||||
|
||||
// Data timeout
|
||||
#define AP_RANGEFINDER_MSP_TIMEOUT_MS 500
|
||||
|
||||
|
|
|
@ -1,14 +1,12 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_RangeFinder_config.h"
|
||||
|
||||
#if AP_RANGEFINDER_MAXSONARI2CXL_ENABLED
|
||||
|
||||
#include "AP_RangeFinder.h"
|
||||
#include "AP_RangeFinder_Backend.h"
|
||||
|
||||
#ifndef AP_RANGEFINDER_MAXSONARI2CXL_ENABLED
|
||||
#define AP_RANGEFINDER_MAXSONARI2CXL_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#if AP_RANGEFINDER_MAXSONARI2CXL_ENABLED
|
||||
|
||||
#include <AP_HAL/I2CDevice.h>
|
||||
|
||||
#define AP_RANGE_FINDER_MAXSONARI2CXL_DEFAULT_ADDR 0x70
|
||||
|
|
|
@ -1,14 +1,12 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_RangeFinder_config.h"
|
||||
|
||||
#if AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED
|
||||
|
||||
#include "AP_RangeFinder.h"
|
||||
#include "AP_RangeFinder_Backend_Serial.h"
|
||||
|
||||
#ifndef AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED
|
||||
#define AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#if AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED
|
||||
|
||||
class AP_RangeFinder_MaxsonarSerialLV : public AP_RangeFinder_Backend_Serial
|
||||
{
|
||||
|
||||
|
|
|
@ -15,15 +15,13 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "AP_RangeFinder.h"
|
||||
#include "AP_RangeFinder_Backend_Serial.h"
|
||||
|
||||
#ifndef AP_RANGEFINDER_NMEA_ENABLED
|
||||
#define AP_RANGEFINDER_NMEA_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
#include "AP_RangeFinder_config.h"
|
||||
|
||||
#if AP_RANGEFINDER_NMEA_ENABLED
|
||||
|
||||
#include "AP_RangeFinder.h"
|
||||
#include "AP_RangeFinder_Backend_Serial.h"
|
||||
|
||||
class AP_RangeFinder_NMEA : public AP_RangeFinder_Backend_Serial
|
||||
{
|
||||
|
||||
|
|
|
@ -1,13 +1,10 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_RangeFinder.h"
|
||||
|
||||
#ifndef AP_RANGEFINDER_NOOPLOOP_ENABLED
|
||||
#define AP_RANGEFINDER_NOOPLOOP_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED && BOARD_FLASH_SIZE > 1024
|
||||
#endif
|
||||
#include "AP_RangeFinder_config.h"
|
||||
|
||||
#if AP_RANGEFINDER_NOOPLOOP_ENABLED
|
||||
|
||||
#include "AP_RangeFinder.h"
|
||||
#include "AP_RangeFinder_Backend_Serial.h"
|
||||
|
||||
class AP_RangeFinder_NoopLoop : public AP_RangeFinder_Backend_Serial
|
||||
|
|
|
@ -14,17 +14,13 @@
|
|||
*/
|
||||
#pragma once
|
||||
|
||||
#include "AP_RangeFinder.h"
|
||||
#include "AP_RangeFinder_Backend.h"
|
||||
|
||||
#ifndef AP_RANGEFINDER_PWM_ENABLED
|
||||
#define AP_RANGEFINDER_PWM_ENABLED \
|
||||
(CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && \
|
||||
AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED)
|
||||
#endif
|
||||
#include "AP_RangeFinder_config.h"
|
||||
|
||||
#if AP_RANGEFINDER_PWM_ENABLED
|
||||
|
||||
#include "AP_RangeFinder.h"
|
||||
#include "AP_RangeFinder_Backend.h"
|
||||
|
||||
class AP_RangeFinder_PWM : public AP_RangeFinder_Backend
|
||||
{
|
||||
public:
|
||||
|
|
|
@ -1,14 +1,12 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_RangeFinder_config.h"
|
||||
|
||||
#if AP_RANGEFINDER_PULSEDLIGHTLRF_ENABLED
|
||||
|
||||
#include "AP_RangeFinder.h"
|
||||
#include "AP_RangeFinder_Backend.h"
|
||||
|
||||
#ifndef AP_RANGEFINDER_PULSEDLIGHTLRF_ENABLED
|
||||
#define AP_RANGEFINDER_PULSEDLIGHTLRF_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#if AP_RANGEFINDER_PULSEDLIGHTLRF_ENABLED
|
||||
|
||||
#include <AP_HAL/I2CDevice.h>
|
||||
|
||||
/* Connection diagram
|
||||
|
|
|
@ -1,14 +1,12 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_RangeFinder_config.h"
|
||||
|
||||
#if AP_RANGEFINDER_TRI2C_ENABLED
|
||||
|
||||
#include "AP_RangeFinder.h"
|
||||
#include "AP_RangeFinder_Backend.h"
|
||||
|
||||
#ifndef AP_RANGEFINDER_TRI2C_ENABLED
|
||||
#define AP_RANGEFINDER_TRI2C_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#if AP_RANGEFINDER_TRI2C_ENABLED
|
||||
|
||||
#include <AP_HAL/I2CDevice.h>
|
||||
|
||||
class AP_RangeFinder_TeraRangerI2C : public AP_RangeFinder_Backend
|
||||
|
|
|
@ -1,14 +1,12 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_RangeFinder_config.h"
|
||||
|
||||
#if AP_RANGEFINDER_TERARANGER_SERIAL_ENABLED
|
||||
|
||||
#include "AP_RangeFinder.h"
|
||||
#include "AP_RangeFinder_Backend_Serial.h"
|
||||
|
||||
#ifndef AP_RANGEFINDER_TERARANGER_SERIAL_ENABLED
|
||||
#define AP_RANGEFINDER_TERARANGER_SERIAL_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#if AP_RANGEFINDER_TERARANGER_SERIAL_ENABLED
|
||||
|
||||
class AP_RangeFinder_TeraRanger_Serial : public AP_RangeFinder_Backend_Serial
|
||||
{
|
||||
|
||||
|
|
|
@ -1,14 +1,12 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_RangeFinder_config.h"
|
||||
|
||||
#if AP_RANGEFINDER_USD1_CAN_ENABLED
|
||||
|
||||
#include "AP_RangeFinder_Backend.h"
|
||||
#include <AP_CANManager/AP_CANSensor.h>
|
||||
|
||||
#ifndef AP_RANGEFINDER_USD1_CAN_ENABLED
|
||||
#define AP_RANGEFINDER_USD1_CAN_ENABLED (HAL_MAX_CAN_PROTOCOL_DRIVERS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED)
|
||||
#endif
|
||||
|
||||
#if AP_RANGEFINDER_USD1_CAN_ENABLED
|
||||
|
||||
class USD1_MultiCAN;
|
||||
|
||||
class AP_RangeFinder_USD1_CAN : public AP_RangeFinder_Backend {
|
||||
|
|
|
@ -1,15 +1,13 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_RangeFinder_config.h"
|
||||
|
||||
#if AP_RANGEFINDER_VL53L0X_ENABLED
|
||||
|
||||
#include "AP_RangeFinder.h"
|
||||
#include "AP_RangeFinder_Backend.h"
|
||||
#include <AP_HAL/I2CDevice.h>
|
||||
|
||||
#ifndef AP_RANGEFINDER_VL53L0X_ENABLED
|
||||
#define AP_RANGEFINDER_VL53L0X_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#if AP_RANGEFINDER_VL53L0X_ENABLED
|
||||
|
||||
class AP_RangeFinder_VL53L0X : public AP_RangeFinder_Backend
|
||||
{
|
||||
|
||||
|
|
|
@ -1,14 +1,12 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_RangeFinder_config.h"
|
||||
|
||||
#if AP_RANGEFINDER_VL53L1X_ENABLED
|
||||
|
||||
#include "AP_RangeFinder.h"
|
||||
#include "AP_RangeFinder_Backend.h"
|
||||
|
||||
#ifndef AP_RANGEFINDER_VL53L1X_ENABLED
|
||||
#define AP_RANGEFINDER_VL53L1X_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#if AP_RANGEFINDER_VL53L1X_ENABLED
|
||||
|
||||
#include <AP_HAL/I2CDevice.h>
|
||||
|
||||
class AP_RangeFinder_VL53L1X : public AP_RangeFinder_Backend
|
||||
|
|
|
@ -1,14 +1,12 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_RangeFinder_config.h"
|
||||
|
||||
#if AP_RANGEFINDER_WASP_ENABLED
|
||||
|
||||
#include "AP_RangeFinder.h"
|
||||
#include "AP_RangeFinder_Backend_Serial.h"
|
||||
|
||||
#ifndef AP_RANGEFINDER_WASP_ENABLED
|
||||
#define AP_RANGEFINDER_WASP_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#if AP_RANGEFINDER_WASP_ENABLED
|
||||
|
||||
// WASP 200 LRF
|
||||
// http://www.attolloengineering.com/wasp-200-lrf.html
|
||||
|
||||
|
|
|
@ -2,6 +2,8 @@
|
|||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
#include <AP_Scripting/AP_Scripting_config.h>
|
||||
#include <AP_CANManager/AP_CANManager_config.h>
|
||||
#include <AP_MSP/AP_MSP_config.h>
|
||||
|
||||
#ifndef AP_RANGEFINDER_ENABLED
|
||||
#define AP_RANGEFINDER_ENABLED 1
|
||||
|
@ -22,6 +24,30 @@
|
|||
)
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_BENEWAKE_ENABLED
|
||||
#define AP_RANGEFINDER_BENEWAKE_ENABLED AP_RANGEFINDER_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_BENEWAKE_CAN_ENABLED
|
||||
#define AP_RANGEFINDER_BENEWAKE_CAN_ENABLED (HAL_MAX_CAN_PROTOCOL_DRIVERS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED)
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_BENEWAKE_TF02_ENABLED
|
||||
#define AP_RANGEFINDER_BENEWAKE_TF02_ENABLED (AP_RANGEFINDER_BENEWAKE_ENABLED && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED)
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_BENEWAKE_TF03_ENABLED
|
||||
#define AP_RANGEFINDER_BENEWAKE_TF03_ENABLED (AP_RANGEFINDER_BENEWAKE_ENABLED && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED)
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_BENEWAKE_TFMINI_ENABLED
|
||||
#define AP_RANGEFINDER_BENEWAKE_TFMINI_ENABLED (AP_RANGEFINDER_BENEWAKE_ENABLED && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED)
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_BENEWAKE_TFMINIPLUS_ENABLED
|
||||
#define AP_RANGEFINDER_BENEWAKE_TFMINIPLUS_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_BLPING_ENABLED
|
||||
#define AP_RANGEFINDER_BLPING_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
@ -34,10 +60,98 @@
|
|||
defined(HAVE_LIBIIO)
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_DRONECAN_ENABLED
|
||||
#define AP_RANGEFINDER_DRONECAN_ENABLED (HAL_ENABLE_DRONECAN_DRIVERS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED)
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_GYUS42V2_ENABLED
|
||||
#define AP_RANGEFINDER_GYUS42V2_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_HC_SR04_ENABLED
|
||||
#define AP_RANGEFINDER_HC_SR04_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_LANBAO_ENABLED
|
||||
#define AP_RANGEFINDER_LANBAO_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_LEDDARONE_ENABLED
|
||||
#define AP_RANGEFINDER_LEDDARONE_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_LEDDARVU8_ENABLED
|
||||
#define AP_RANGEFINDER_LEDDARVU8_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_LWI2C_ENABLED
|
||||
#define AP_RANGEFINDER_LWI2C_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED
|
||||
#define AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_LUA_ENABLED
|
||||
#define AP_RANGEFINDER_LUA_ENABLED AP_SCRIPTING_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_MAVLINK_ENABLED
|
||||
#define AP_RANGEFINDER_MAVLINK_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED
|
||||
#define AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_MAXSONARI2CXL_ENABLED
|
||||
#define AP_RANGEFINDER_MAXSONARI2CXL_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef HAL_MSP_RANGEFINDER_ENABLED
|
||||
#define HAL_MSP_RANGEFINDER_ENABLED HAL_MSP_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_NMEA_ENABLED
|
||||
#define AP_RANGEFINDER_NMEA_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_NOOPLOOP_ENABLED
|
||||
#define AP_RANGEFINDER_NOOPLOOP_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED && BOARD_FLASH_SIZE > 1024
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_PWM_ENABLED
|
||||
#define AP_RANGEFINDER_PWM_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED)
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_PULSEDLIGHTLRF_ENABLED
|
||||
#define AP_RANGEFINDER_PULSEDLIGHTLRF_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_SIM_ENABLED
|
||||
#define AP_RANGEFINDER_SIM_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED)
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_TERARANGER_SERIAL_ENABLED
|
||||
#define AP_RANGEFINDER_TERARANGER_SERIAL_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_TRI2C_ENABLED
|
||||
#define AP_RANGEFINDER_TRI2C_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_USD1_CAN_ENABLED
|
||||
#define AP_RANGEFINDER_USD1_CAN_ENABLED (HAL_MAX_CAN_PROTOCOL_DRIVERS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED)
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_VL53L0X_ENABLED
|
||||
#define AP_RANGEFINDER_VL53L0X_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_VL53L1X_ENABLED
|
||||
#define AP_RANGEFINDER_VL53L1X_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_RANGEFINDER_WASP_ENABLED
|
||||
#define AP_RANGEFINDER_WASP_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue