AP_RangeFinder: allow rangefinder backends to be individually compiled in

This commit is contained in:
Peter Barker 2022-03-12 21:37:29 +11:00 committed by Andrew Tridgell
parent ce1bb906b7
commit 3a347d32ca
61 changed files with 430 additions and 68 deletions

View File

@ -41,6 +41,7 @@
#include "AP_RangeFinder_PWM.h" #include "AP_RangeFinder_PWM.h"
#include "AP_RangeFinder_GYUS42v2.h" #include "AP_RangeFinder_GYUS42v2.h"
#include "AP_RangeFinder_HC_SR04.h" #include "AP_RangeFinder_HC_SR04.h"
#include "AP_RangeFinder_Bebop.h"
#include "AP_RangeFinder_BLPing.h" #include "AP_RangeFinder_BLPing.h"
#include "AP_RangeFinder_UAVCAN.h" #include "AP_RangeFinder_UAVCAN.h"
#include "AP_RangeFinder_Lanbao.h" #include "AP_RangeFinder_Lanbao.h"
@ -347,14 +348,17 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
case Type::PLI2C: case Type::PLI2C:
case Type::PLI2CV3: case Type::PLI2CV3:
case Type::PLI2CV3HP: case Type::PLI2CV3HP:
#if AP_RANGEFINDER_PULSEDLIGHTLRF_ENABLED
FOREACH_I2C(i) { FOREACH_I2C(i) {
if (_add_backend(AP_RangeFinder_PulsedLightLRF::detect(i, state[instance], params[instance], _type), if (_add_backend(AP_RangeFinder_PulsedLightLRF::detect(i, state[instance], params[instance], _type),
instance)) { instance)) {
break; break;
} }
} }
#endif
break; break;
case Type::MBI2C: { case Type::MBI2C: {
#if AP_RANGEFINDER_MAXSONARI2CXL_ENABLED
uint8_t addr = AP_RANGE_FINDER_MAXSONARI2CXL_DEFAULT_ADDR; uint8_t addr = AP_RANGE_FINDER_MAXSONARI2CXL_DEFAULT_ADDR;
if (params[instance].address != 0) { if (params[instance].address != 0) {
addr = params[instance].address; addr = params[instance].address;
@ -367,8 +371,10 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
} }
} }
break; break;
#endif
} }
case Type::LWI2C: case Type::LWI2C:
#if AP_RANGEFINDER_LWI2C_ENABLED
if (params[instance].address) { if (params[instance].address) {
// the LW20 needs a long time to boot up, so we delay 1.5s here // the LW20 needs a long time to boot up, so we delay 1.5s here
if (!hal.util->was_watchdog_armed()) { if (!hal.util->was_watchdog_armed()) {
@ -388,8 +394,10 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
} }
#endif #endif
} }
#endif // AP_RANGEFINDER_LWI2C_ENABLED
break; break;
case Type::TRI2C: case Type::TRI2C:
#if AP_RANGEFINDER_TRI2C_ENABLED
if (params[instance].address) { if (params[instance].address) {
FOREACH_I2C(i) { FOREACH_I2C(i) {
if (_add_backend(AP_RangeFinder_TeraRangerI2C::detect(state[instance], params[instance], if (_add_backend(AP_RangeFinder_TeraRangerI2C::detect(state[instance], params[instance],
@ -399,15 +407,19 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
} }
} }
} }
#endif
break; break;
case Type::VL53L0X: case Type::VL53L0X:
case Type::VL53L1X_Short: case Type::VL53L1X_Short:
FOREACH_I2C(i) { FOREACH_I2C(i) {
#if AP_RANGEFINDER_VL53L0X_ENABLED
if (_add_backend(AP_RangeFinder_VL53L0X::detect(state[instance], params[instance], if (_add_backend(AP_RangeFinder_VL53L0X::detect(state[instance], params[instance],
hal.i2c_mgr->get_device(i, params[instance].address)), hal.i2c_mgr->get_device(i, params[instance].address)),
instance)) { instance)) {
break; break;
} }
#endif
#if AP_RANGEFINDER_VL53L1X_ENABLED
if (_add_backend(AP_RangeFinder_VL53L1X::detect(state[instance], params[instance], if (_add_backend(AP_RangeFinder_VL53L1X::detect(state[instance], params[instance],
hal.i2c_mgr->get_device(i, params[instance].address), hal.i2c_mgr->get_device(i, params[instance].address),
_type == Type::VL53L1X_Short ? AP_RangeFinder_VL53L1X::DistanceMode::Short : _type == Type::VL53L1X_Short ? AP_RangeFinder_VL53L1X::DistanceMode::Short :
@ -415,9 +427,11 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
instance)) { instance)) {
break; break;
} }
#endif
} }
break; break;
case Type::BenewakeTFminiPlus: { case Type::BenewakeTFminiPlus: {
#if AP_RANGEFINDER_BENEWAKE_TFMINIPLUS_ENABLED
uint8_t addr = TFMINI_ADDR_DEFAULT; uint8_t addr = TFMINI_ADDR_DEFAULT;
if (params[instance].address != 0) { if (params[instance].address != 0) {
addr = params[instance].address; addr = params[instance].address;
@ -430,62 +444,68 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
} }
} }
break; break;
#endif
} }
case Type::PX4_PWM: case Type::PX4_PWM:
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS #if AP_RANGEFINDER_PWM_ENABLED
#ifndef HAL_BUILD_AP_PERIPH
// to ease moving from PX4 to ChibiOS we'll lie a little about // to ease moving from PX4 to ChibiOS we'll lie a little about
// the backend driver... // the backend driver...
if (AP_RangeFinder_PWM::detect()) { if (AP_RangeFinder_PWM::detect()) {
_add_backend(new AP_RangeFinder_PWM(state[instance], params[instance], estimated_terrain_height), instance); _add_backend(new AP_RangeFinder_PWM(state[instance], params[instance], estimated_terrain_height), instance);
} }
#endif
#endif #endif
break; break;
case Type::BBB_PRU: case Type::BBB_PRU:
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI #if AP_RANGEFINDER_BBB_PRU_ENABLED
if (AP_RangeFinder_BBB_PRU::detect()) { if (AP_RangeFinder_BBB_PRU::detect()) {
_add_backend(new AP_RangeFinder_BBB_PRU(state[instance], params[instance]), instance); _add_backend(new AP_RangeFinder_BBB_PRU(state[instance], params[instance]), instance);
} }
#endif #endif
break; break;
case Type::LWSER: case Type::LWSER:
#if AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED
if (AP_RangeFinder_LightWareSerial::detect(serial_instance)) { if (AP_RangeFinder_LightWareSerial::detect(serial_instance)) {
_add_backend(new AP_RangeFinder_LightWareSerial(state[instance], params[instance]), instance, serial_instance++); _add_backend(new AP_RangeFinder_LightWareSerial(state[instance], params[instance]), instance, serial_instance++);
} }
#endif
break; break;
case Type::LEDDARONE: case Type::LEDDARONE:
#if AP_RANGEFINDER_LEDDARONE_ENABLED
if (AP_RangeFinder_LeddarOne::detect(serial_instance)) { if (AP_RangeFinder_LeddarOne::detect(serial_instance)) {
_add_backend(new AP_RangeFinder_LeddarOne(state[instance], params[instance]), instance, serial_instance++); _add_backend(new AP_RangeFinder_LeddarOne(state[instance], params[instance]), instance, serial_instance++);
} }
#endif
break; break;
case Type::USD1_Serial: case Type::USD1_Serial:
#if AP_RANGEFINDER_USD1_SERIAL_ENABLED
if (AP_RangeFinder_USD1_Serial::detect(serial_instance)) { if (AP_RangeFinder_USD1_Serial::detect(serial_instance)) {
_add_backend(new AP_RangeFinder_USD1_Serial(state[instance], params[instance]), instance, serial_instance++); _add_backend(new AP_RangeFinder_USD1_Serial(state[instance], params[instance]), instance, serial_instance++);
} }
#endif
break; break;
case Type::BEBOP: case Type::BEBOP:
#if (CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || \ #if AP_RANGEFINDER_BEBOP_ENABLED
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO) && defined(HAVE_LIBIIO)
if (AP_RangeFinder_Bebop::detect()) { if (AP_RangeFinder_Bebop::detect()) {
_add_backend(new AP_RangeFinder_Bebop(state[instance], params[instance]), instance); _add_backend(new AP_RangeFinder_Bebop(state[instance], params[instance]), instance);
} }
#endif #endif
break; break;
case Type::MAVLink: case Type::MAVLink:
#ifndef HAL_BUILD_AP_PERIPH #if AP_RANGEFINDER_MAVLINK_ENABLED
if (AP_RangeFinder_MAVLink::detect()) { if (AP_RangeFinder_MAVLink::detect()) {
_add_backend(new AP_RangeFinder_MAVLink(state[instance], params[instance]), instance); _add_backend(new AP_RangeFinder_MAVLink(state[instance], params[instance]), instance);
} }
#endif #endif
break; break;
case Type::MBSER: case Type::MBSER:
#if AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED
if (AP_RangeFinder_MaxsonarSerialLV::detect(serial_instance)) { if (AP_RangeFinder_MaxsonarSerialLV::detect(serial_instance)) {
_add_backend(new AP_RangeFinder_MaxsonarSerialLV(state[instance], params[instance]), instance, serial_instance++); _add_backend(new AP_RangeFinder_MaxsonarSerialLV(state[instance], params[instance]), instance, serial_instance++);
} }
#endif
break; break;
case Type::ANALOG: case Type::ANALOG:
#ifndef HAL_BUILD_AP_PERIPH #if AP_RANGEFINDER_ANALOG_ENABLED
// note that analog will always come back as present if the pin is valid // note that analog will always come back as present if the pin is valid
if (AP_RangeFinder_analog::detect(params[instance])) { if (AP_RangeFinder_analog::detect(params[instance])) {
_add_backend(new AP_RangeFinder_analog(state[instance], params[instance]), instance); _add_backend(new AP_RangeFinder_analog(state[instance], params[instance]), instance);
@ -493,7 +513,7 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
#endif #endif
break; break;
case Type::HC_SR04: case Type::HC_SR04:
#ifndef HAL_BUILD_AP_PERIPH #if AP_RANGEFINDER_HC_SR04_ENABLED
// note that this will always come back as present if the pin is valid // note that this will always come back as present if the pin is valid
if (AP_RangeFinder_HC_SR04::detect(params[instance])) { if (AP_RangeFinder_HC_SR04::detect(params[instance])) {
_add_backend(new AP_RangeFinder_HC_SR04(state[instance], params[instance]), instance); _add_backend(new AP_RangeFinder_HC_SR04(state[instance], params[instance]), instance);
@ -501,55 +521,71 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
#endif #endif
break; break;
case Type::NMEA: case Type::NMEA:
#if AP_RANGEFINDER_NMEA_ENABLED
if (AP_RangeFinder_NMEA::detect(serial_instance)) { if (AP_RangeFinder_NMEA::detect(serial_instance)) {
_add_backend(new AP_RangeFinder_NMEA(state[instance], params[instance]), instance, serial_instance++); _add_backend(new AP_RangeFinder_NMEA(state[instance], params[instance]), instance, serial_instance++);
} }
#endif
break; break;
case Type::WASP: case Type::WASP:
#if AP_RANGEFINDER_WASP_ENABLED
if (AP_RangeFinder_Wasp::detect(serial_instance)) { if (AP_RangeFinder_Wasp::detect(serial_instance)) {
_add_backend(new AP_RangeFinder_Wasp(state[instance], params[instance]), instance, serial_instance++); _add_backend(new AP_RangeFinder_Wasp(state[instance], params[instance]), instance, serial_instance++);
} }
#endif
break; break;
case Type::BenewakeTF02: case Type::BenewakeTF02:
#if AP_RANGEFINDER_BENEWAKE_TF02_ENABLED
if (AP_RangeFinder_Benewake_TF02::detect(serial_instance)) { if (AP_RangeFinder_Benewake_TF02::detect(serial_instance)) {
_add_backend(new AP_RangeFinder_Benewake_TF02(state[instance], params[instance]), instance, serial_instance++); _add_backend(new AP_RangeFinder_Benewake_TF02(state[instance], params[instance]), instance, serial_instance++);
} }
#endif
break; break;
case Type::BenewakeTFmini: case Type::BenewakeTFmini:
#if AP_RANGEFINDER_BENEWAKE_TFMINI_ENABLED
if (AP_RangeFinder_Benewake_TFMini::detect(serial_instance)) { if (AP_RangeFinder_Benewake_TFMini::detect(serial_instance)) {
_add_backend(new AP_RangeFinder_Benewake_TFMini(state[instance], params[instance]), instance, serial_instance++); _add_backend(new AP_RangeFinder_Benewake_TFMini(state[instance], params[instance]), instance, serial_instance++);
} }
#endif
break; break;
case Type::BenewakeTF03: case Type::BenewakeTF03:
#if AP_RANGEFINDER_BENEWAKE_TF03_ENABLED
if (AP_RangeFinder_Benewake_TF03::detect(serial_instance)) { if (AP_RangeFinder_Benewake_TF03::detect(serial_instance)) {
_add_backend(new AP_RangeFinder_Benewake_TF03(state[instance], params[instance]), instance, serial_instance++); _add_backend(new AP_RangeFinder_Benewake_TF03(state[instance], params[instance]), instance, serial_instance++);
} }
#endif
break; break;
case Type::PWM: case Type::PWM:
#ifndef HAL_BUILD_AP_PERIPH #if AP_RANGEFINDER_PWM_ENABLED
if (AP_RangeFinder_PWM::detect()) { if (AP_RangeFinder_PWM::detect()) {
_add_backend(new AP_RangeFinder_PWM(state[instance], params[instance], estimated_terrain_height), instance); _add_backend(new AP_RangeFinder_PWM(state[instance], params[instance], estimated_terrain_height), instance);
} }
#endif #endif
break; break;
case Type::BLPing: case Type::BLPing:
#if AP_RANGEFINDER_BLPING_ENABLED
if (AP_RangeFinder_BLPing::detect(serial_instance)) { if (AP_RangeFinder_BLPing::detect(serial_instance)) {
_add_backend(new AP_RangeFinder_BLPing(state[instance], params[instance]), instance, serial_instance++); _add_backend(new AP_RangeFinder_BLPing(state[instance], params[instance]), instance, serial_instance++);
} }
#endif
break; break;
case Type::Lanbao: case Type::Lanbao:
#if AP_RANGEFINDER_LANBAO_ENABLED
if (AP_RangeFinder_Lanbao::detect(serial_instance)) { if (AP_RangeFinder_Lanbao::detect(serial_instance)) {
_add_backend(new AP_RangeFinder_Lanbao(state[instance], params[instance]), instance, serial_instance++); _add_backend(new AP_RangeFinder_Lanbao(state[instance], params[instance]), instance, serial_instance++);
} }
#endif
break; break;
case Type::LeddarVu8_Serial: case Type::LeddarVu8_Serial:
#if AP_RANGEFINDER_LEDDARVU8_ENABLED
if (AP_RangeFinder_LeddarVu8::detect(serial_instance)) { if (AP_RangeFinder_LeddarVu8::detect(serial_instance)) {
_add_backend(new AP_RangeFinder_LeddarVu8(state[instance], params[instance]), instance, serial_instance++); _add_backend(new AP_RangeFinder_LeddarVu8(state[instance], params[instance]), instance, serial_instance++);
} }
#endif
break; break;
case Type::UAVCAN: case Type::UAVCAN:
#if HAL_CANMANAGER_ENABLED #if AP_RANGEFINDER_UAVCAN_ENABLED
/* /*
the UAVCAN driver gets created when we first receive a the UAVCAN driver gets created when we first receive a
measurement. We take the instance slot now, even if we don't measurement. We take the instance slot now, even if we don't
@ -560,13 +596,15 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
break; break;
case Type::GYUS42v2: case Type::GYUS42v2:
#if AP_RANGEFINDER_GYUS42V2_ENABLED
if (AP_RangeFinder_GYUS42v2::detect(serial_instance)) { if (AP_RangeFinder_GYUS42v2::detect(serial_instance)) {
_add_backend(new AP_RangeFinder_GYUS42v2(state[instance], params[instance]), instance, serial_instance++); _add_backend(new AP_RangeFinder_GYUS42v2(state[instance], params[instance]), instance, serial_instance++);
} }
#endif
break; break;
case Type::SIM: case Type::SIM:
#if AP_SIM_RANGEFINDER_ENABLED #if AP_RANGEFINDER_SIM_ENABLED
_add_backend(new AP_RangeFinder_SITL(state[instance], params[instance], instance), instance); _add_backend(new AP_RangeFinder_SITL(state[instance], params[instance], instance), instance);
#endif #endif
break; break;
@ -579,16 +617,17 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
#endif // HAL_MSP_RANGEFINDER_ENABLED #endif // HAL_MSP_RANGEFINDER_ENABLED
break; break;
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
case Type::USD1_CAN: case Type::USD1_CAN:
#if AP_RANGEFINDER_USD1_CAN_ENABLED
_add_backend(new AP_RangeFinder_USD1_CAN(state[instance], params[instance]), instance); _add_backend(new AP_RangeFinder_USD1_CAN(state[instance], params[instance]), instance);
#endif
break; break;
case Type::Benewake_CAN: case Type::Benewake_CAN:
#if AP_RANGEFINDER_BENEWAKE_CAN_ENABLED
_add_backend(new AP_RangeFinder_Benewake_CAN(state[instance], params[instance]), instance); _add_backend(new AP_RangeFinder_Benewake_CAN(state[instance], params[instance]), instance);
break; break;
#endif //HAL_MAX_CAN_PROTOCOL_DRIVERS #endif
case Type::NONE: case Type::NONE:
default:
break; break;
} }

View File

@ -26,6 +26,10 @@
#define AP_RANGEFINDER_ENABLED 1 #define AP_RANGEFINDER_ENABLED 1
#endif #endif
#ifndef AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
#define AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED AP_RANGEFINDER_ENABLED
#endif
// Maximum number of range finder instances available on this platform // Maximum number of range finder instances available on this platform
#ifndef RANGEFINDER_MAX_INSTANCES #ifndef RANGEFINDER_MAX_INSTANCES
#if AP_RANGEFINDER_ENABLED #if AP_RANGEFINDER_ENABLED

View File

@ -16,11 +16,10 @@
by Mirko Denecke <mirkix@gmail.com> by Mirko Denecke <mirkix@gmail.com>
*/ */
#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI
#include "AP_RangeFinder_BBB_PRU.h" #include "AP_RangeFinder_BBB_PRU.h"
#if AP_RANGEFINDER_BBB_PRU_ENABLED
#include <stdio.h> #include <stdio.h>
#include <stdlib.h> #include <stdlib.h>
#include <stdint.h> #include <stdint.h>
@ -105,4 +104,4 @@ void AP_RangeFinder_BBB_PRU::update(void)
state.distance_m = rangerpru->distance * 0.01f; state.distance_m = rangerpru->distance * 0.01f;
state.last_reading_ms = AP_HAL::millis(); state.last_reading_ms = AP_HAL::millis();
} }
#endif // CONFIG_HAL_BOARD_SUBTYPE #endif // AP_RANGEFINDER_BBB_PRU_ENABLED

View File

@ -3,6 +3,16 @@
#include "AP_RangeFinder.h" #include "AP_RangeFinder.h"
#include "AP_RangeFinder_Backend.h" #include "AP_RangeFinder_Backend.h"
#include <AP_BoardConfig/AP_BoardConfig.h>
#ifndef AP_RANGEFINDER_BBB_PRU_ENABLED
#define AP_RANGEFINDER_BBB_PRU_ENABLED ( \
AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED && \
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI \
)
#endif
#if AP_RANGEFINDER_BBB_PRU_ENABLED
#define PRU0_CTRL_BASE 0x4a322000 #define PRU0_CTRL_BASE 0x4a322000
@ -43,3 +53,5 @@ protected:
private: private:
}; };
#endif

View File

@ -13,10 +13,12 @@
along with this program. If not, see <http://www.gnu.org/licenses/>. along with this program. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include <AP_HAL/AP_HAL.h>
#include <GCS_MAVLink/GCS.h>
#include "AP_RangeFinder_BLPing.h" #include "AP_RangeFinder_BLPing.h"
#if AP_RANGEFINDER_BLPING_ENABLED
#include <AP_HAL/AP_HAL.h>
void AP_RangeFinder_BLPing::update(void) void AP_RangeFinder_BLPing::update(void)
{ {
if (uart == nullptr) { if (uart == nullptr) {
@ -226,3 +228,5 @@ PingProtocol::MessageId PingProtocol::parse_byte(uint8_t b)
return msg.done ? get_message_id() : MessageId::INVALID; return msg.done ? get_message_id() : MessageId::INVALID;
} }
#endif // AP_RANGEFINDER_BLPING_ENABLED

View File

@ -1,6 +1,13 @@
#pragma once #pragma once
#include "AP_RangeFinder.h" #include "AP_RangeFinder.h"
#ifndef AP_RANGEFINDER_BLPING_ENABLED
#define AP_RANGEFINDER_BLPING_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
#endif
#if AP_RANGEFINDER_BLPING_ENABLED
#include "AP_RangeFinder_Backend_Serial.h" #include "AP_RangeFinder_Backend_Serial.h"
/** /**
@ -170,3 +177,5 @@ private:
*/ */
uint32_t last_init_ms; uint32_t last_init_ms;
}; };
#endif

View File

@ -12,13 +12,14 @@
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>. along with this program. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include "AP_RangeFinder_Bebop.h"
#if AP_RANGEFINDER_BEBOP_ENABLED
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <utility> #include <utility>
#if (CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || \
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO) && \
defined(HAVE_LIBIIO)
#include <stdlib.h> #include <stdlib.h>
#include <unistd.h> #include <unistd.h>
#include <stdio.h> #include <stdio.h>
@ -32,7 +33,6 @@
#include <math.h> #include <math.h>
#include <time.h> #include <time.h>
#include <iio.h> #include <iio.h>
#include "AP_RangeFinder_Bebop.h"
#include <AP_HAL_Linux/Thread.h> #include <AP_HAL_Linux/Thread.h>
#include <AP_HAL_Linux/GPIO.h> #include <AP_HAL_Linux/GPIO.h>
@ -474,4 +474,5 @@ int AP_RangeFinder_Bebop::_update_mode(float altitude)
} }
return _mode; return _mode;
} }
#endif
#endif // AP_RANGEFINDER_BEBOP_ENABLED

View File

@ -16,6 +16,20 @@
#include "AP_RangeFinder.h" #include "AP_RangeFinder.h"
#include "AP_RangeFinder_Backend.h" #include "AP_RangeFinder_Backend.h"
#include <AP_HAL/AP_HAL.h>
#include <utility>
#ifndef AP_RANGEFINDER_BEBOP_ENABLED
#define AP_RANGEFINDER_BEBOP_ENABLED \
AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED && \
(CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || \
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO) && \
defined(HAVE_LIBIIO)
#endif
#if AP_RANGEFINDER_BEBOP_ENABLED
#include <AP_HAL_Linux/Thread.h> #include <AP_HAL_Linux/Thread.h>
/* /*
@ -143,3 +157,5 @@ private:
int16_t _last_min_distance_cm = 32; int16_t _last_min_distance_cm = 32;
}; };
#endif

View File

@ -15,6 +15,8 @@
#include "AP_RangeFinder_Benewake.h" #include "AP_RangeFinder_Benewake.h"
#if AP_RANGEFINDER_BENEWAKE_ENABLED
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_HAL/utility/sparse-endian.h> #include <AP_HAL/utility/sparse-endian.h>
@ -132,3 +134,5 @@ bool AP_RangeFinder_Benewake::get_reading(float &reading_m)
// no readings so return false // no readings so return false
return false; return false;
} }
#endif // AP_RANGEFINDER_BENEWAKE_ENABLED

View File

@ -1,6 +1,13 @@
#pragma once #pragma once
#include "AP_RangeFinder.h" #include "AP_RangeFinder.h"
#ifndef AP_RANGEFINDER_BENEWAKE_ENABLED
#define AP_RANGEFINDER_BENEWAKE_ENABLED AP_RANGEFINDER_ENABLED
#endif
#if AP_RANGEFINDER_BENEWAKE_ENABLED
#include "AP_RangeFinder_Backend_Serial.h" #include "AP_RangeFinder_Backend_Serial.h"
class AP_RangeFinder_Benewake : public AP_RangeFinder_Backend_Serial class AP_RangeFinder_Benewake : public AP_RangeFinder_Backend_Serial
@ -28,3 +35,5 @@ private:
uint8_t linebuf[10]; uint8_t linebuf[10];
uint8_t linebuf_len; uint8_t linebuf_len;
}; };
#endif // AP_RANGEFINDER_BENEWAKE_ENABLED

View File

@ -2,7 +2,7 @@
#include <AP_BoardConfig/AP_BoardConfig.h> #include <AP_BoardConfig/AP_BoardConfig.h>
#include "AP_RangeFinder_Benewake_CAN.h" #include "AP_RangeFinder_Benewake_CAN.h"
#if HAL_MAX_CAN_PROTOCOL_DRIVERS #if AP_RANGEFINDER_BENEWAKE_CAN_ENABLED
const AP_Param::GroupInfo AP_RangeFinder_Benewake_CAN::var_info[] = { const AP_Param::GroupInfo AP_RangeFinder_Benewake_CAN::var_info[] = {
@ -104,4 +104,4 @@ void Benewake_MultiCAN::handle_frame(AP_HAL::CANFrame &frame)
} }
} }
#endif // HAL_MAX_CAN_PROTOCOL_DRIVERS #endif // AP_RANGEFINDER_BENEWAKE_CAN_ENABLED

View File

@ -1,9 +1,14 @@
#pragma once #pragma once
#include "AP_RangeFinder_Backend.h" #include "AP_RangeFinder_Backend.h"
#include <AP_CANManager/AP_CANSensor.h> #include <AP_CANManager/AP_CANSensor.h>
#if HAL_MAX_CAN_PROTOCOL_DRIVERS #ifndef AP_RANGEFINDER_BENEWAKE_CAN_ENABLED
#define AP_RANGEFINDER_BENEWAKE_CAN_ENABLED (HAL_MAX_CAN_PROTOCOL_DRIVERS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED)
#endif
#if AP_RANGEFINDER_BENEWAKE_CAN_ENABLED
class Benewake_MultiCAN; class Benewake_MultiCAN;
@ -52,6 +57,6 @@ public:
AP_RangeFinder_Benewake_CAN *drivers; AP_RangeFinder_Benewake_CAN *drivers;
}; };
#endif //HAL_MAX_CAN_PROTOCOL_DRIVERS #endif // AP_RANGEFINDER_BENEWAKE_CAN_ENABLED

View File

@ -2,6 +2,12 @@
#include "AP_RangeFinder_Benewake.h" #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
#if AP_RANGEFINDER_BENEWAKE_TF02_ENABLED
class AP_RangeFinder_Benewake_TF02 : public AP_RangeFinder_Benewake class AP_RangeFinder_Benewake_TF02 : public AP_RangeFinder_Benewake
{ {
public: public:
@ -11,3 +17,5 @@ protected:
float model_dist_max_cm() const override { return 2200; } float model_dist_max_cm() const override { return 2200; }
bool has_signal_byte() const override { return true; } bool has_signal_byte() const override { return true; }
}; };
#endif // AP_RANGEFINDER_BENEWAKE_TF02_ENABLED

View File

@ -2,6 +2,12 @@
#include "AP_RangeFinder_Benewake.h" #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
#if AP_RANGEFINDER_BENEWAKE_TF03_ENABLED
class AP_RangeFinder_Benewake_TF03 : public AP_RangeFinder_Benewake class AP_RangeFinder_Benewake_TF03 : public AP_RangeFinder_Benewake
{ {
public: public:
@ -10,3 +16,5 @@ public:
protected: protected:
float model_dist_max_cm() const override { return 18000; } float model_dist_max_cm() const override { return 18000; }
}; };
#endif // AP_RANGEFINDER_BENEWAKE_TF03_ENABLED

View File

@ -2,6 +2,12 @@
#include "AP_RangeFinder_Benewake.h" #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
#if AP_RANGEFINDER_BENEWAKE_TFMINI_ENABLED
#define TFMINI_ADDR_DEFAULT 0x10 // TFMini default device id #define TFMINI_ADDR_DEFAULT 0x10 // TFMini default device id
class AP_RangeFinder_Benewake_TFMini : public AP_RangeFinder_Benewake class AP_RangeFinder_Benewake_TFMini : public AP_RangeFinder_Benewake
@ -12,3 +18,5 @@ public:
protected: protected:
float model_dist_max_cm() const override { return 1200; } float model_dist_max_cm() const override { return 1200; }
}; };
#endif // AP_RANGEFINDER_BENEWAKE_TFMINI

View File

@ -16,6 +16,8 @@
*/ */
#include "AP_RangeFinder_Benewake_TFMiniPlus.h" #include "AP_RangeFinder_Benewake_TFMiniPlus.h"
#if AP_RANGEFINDER_BENEWAKE_TFMINIPLUS_ENABLED
#include <utility> #include <utility>
#include <GCS_MAVLink/GCS.h> #include <GCS_MAVLink/GCS.h>
@ -219,3 +221,5 @@ void AP_RangeFinder_Benewake_TFMiniPlus::timer()
accum.count++; accum.count++;
} }
} }
#endif // AP_RANGEFINDER_BENEWAKE_TFMINIPLUS_ENABLED

View File

@ -19,6 +19,12 @@
#include "AP_RangeFinder.h" #include "AP_RangeFinder.h"
#include "AP_RangeFinder_Backend.h" #include "AP_RangeFinder_Backend.h"
#ifndef AP_RANGEFINDER_BENEWAKE_TFMINIPLUS_ENABLED
#define AP_RANGEFINDER_BENEWAKE_TFMINIPLUS_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
#endif
#if AP_RANGEFINDER_BENEWAKE_TFMINIPLUS_ENABLED
#include <AP_HAL/utility/sparse-endian.h> #include <AP_HAL/utility/sparse-endian.h>
#include <AP_HAL/I2CDevice.h> #include <AP_HAL/I2CDevice.h>
@ -60,3 +66,5 @@ private:
uint32_t count; uint32_t count;
} accum; } accum;
}; };
#endif

View File

@ -13,11 +13,9 @@
along with this program. If not, see <http://www.gnu.org/licenses/>. along with this program. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include <AP_HAL/AP_HAL.h>
#include "AP_RangeFinder_GYUS42v2.h" #include "AP_RangeFinder_GYUS42v2.h"
#include <ctype.h>
extern const AP_HAL::HAL& hal; #if AP_RANGEFINDER_GYUS42V2_ENABLED
bool AP_RangeFinder_GYUS42v2::find_signature_in_buffer(uint8_t start) bool AP_RangeFinder_GYUS42v2::find_signature_in_buffer(uint8_t start)
{ {
@ -70,3 +68,5 @@ bool AP_RangeFinder_GYUS42v2::get_reading(float &reading_m)
return true; return true;
} }
#endif // AP_RANGEFINDER_GYUS42V2_ENABLED

View File

@ -1,6 +1,13 @@
#pragma once #pragma once
#include "AP_RangeFinder.h" #include "AP_RangeFinder.h"
#ifndef AP_RANGEFINDER_GYUS42V2_ENABLED
#define AP_RANGEFINDER_GYUS42V2_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
#endif
#if AP_RANGEFINDER_GYUS42V2_ENABLED
#include "AP_RangeFinder_Backend_Serial.h" #include "AP_RangeFinder_Backend_Serial.h"
class AP_RangeFinder_GYUS42v2 : public AP_RangeFinder_Backend_Serial class AP_RangeFinder_GYUS42v2 : public AP_RangeFinder_Backend_Serial
@ -32,3 +39,5 @@ private:
uint8_t buffer[7]; uint8_t buffer[7];
uint8_t buffer_used; uint8_t buffer_used;
}; };
#endif // AP_RANGEFINDER_GYUS42V2_ENABLED

View File

@ -25,10 +25,13 @@
* The second pin we use for triggering the ultransonic pulse * The second pin we use for triggering the ultransonic pulse
*/ */
#include "AP_RangeFinder_HC_SR04.h"
#if AP_RANGEFINDER_HC_SR04_ENABLED
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include "AP_RangeFinder.h" #include "AP_RangeFinder.h"
#include "AP_RangeFinder_Params.h" #include "AP_RangeFinder_Params.h"
#include "AP_RangeFinder_HC_SR04.h"
#include <GCS_MAVLink/GCS.h> #include <GCS_MAVLink/GCS.h>
@ -140,3 +143,4 @@ void AP_RangeFinder_HC_SR04::update(void)
} }
} }
#endif // AP_RANGEFINDER_HC_SR04_ENABLED

View File

@ -2,6 +2,13 @@
#include "AP_RangeFinder.h" #include "AP_RangeFinder.h"
#include "AP_RangeFinder_Backend.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" #include "AP_RangeFinder_Params.h"
class AP_RangeFinder_HC_SR04 : public AP_RangeFinder_Backend class AP_RangeFinder_HC_SR04 : public AP_RangeFinder_Backend
@ -37,3 +44,5 @@ private:
uint32_t last_ping_ms; uint32_t last_ping_ms;
}; };
#endif // AP_RANGEFINDER_HC_SR04_ENABLED

View File

@ -15,8 +15,11 @@
/* /*
driver for Lanbao PSK-CM8JL65-CC5 Lidar driver for Lanbao PSK-CM8JL65-CC5 Lidar
*/ */
#include <AP_HAL/AP_HAL.h>
#include "AP_RangeFinder_Lanbao.h" #include "AP_RangeFinder_Lanbao.h"
#if AP_RANGEFINDER_LANBAO_ENABLED
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/crc.h> #include <AP_Math/crc.h>
#include <stdio.h> #include <stdio.h>
@ -80,3 +83,5 @@ bool AP_RangeFinder_Lanbao::get_reading(float &reading_m)
} }
return false; return false;
} }
#endif // AP_RANGEFINDER_LANBAO_ENABLED

View File

@ -3,6 +3,12 @@
#include "AP_RangeFinder.h" #include "AP_RangeFinder.h"
#include "AP_RangeFinder_Backend_Serial.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 class AP_RangeFinder_Lanbao : public AP_RangeFinder_Backend_Serial
{ {
@ -28,3 +34,5 @@ private:
uint8_t buf[6]; uint8_t buf[6];
uint8_t buf_len = 0; uint8_t buf_len = 0;
}; };
#endif // AP_RANGEFINDER_LANBAO_ENABLED

View File

@ -15,6 +15,8 @@
#include "AP_RangeFinder_LeddarOne.h" #include "AP_RangeFinder_LeddarOne.h"
#if AP_RANGEFINDER_LEDDARONE_ENABLED
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_Math/crc.h> #include <AP_Math/crc.h>
@ -183,3 +185,5 @@ LeddarOne_Status AP_RangeFinder_LeddarOne::parse_response(uint8_t &number_detect
return LEDDARONE_STATE_OK; return LEDDARONE_STATE_OK;
} }
#endif // AP_RANGEFINDER_LEDDARONE_ENABLED

View File

@ -3,6 +3,12 @@
#include "AP_RangeFinder.h" #include "AP_RangeFinder.h"
#include "AP_RangeFinder_Backend_Serial.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 // defines
#define LEDDARONE_DEFAULT_ADDRESS 0x01 #define LEDDARONE_DEFAULT_ADDRESS 0x01
#define LEDDARONE_MODOBUS_FUNCTION_CODE 0x04 #define LEDDARONE_MODOBUS_FUNCTION_CODE 0x04
@ -83,3 +89,5 @@ private:
0x09 // CRC Hi 0x09 // CRC Hi
}; };
}; };
#endif // AP_RANGEFINDER_LEDDARONE_ENABLED

View File

@ -205,4 +205,4 @@ bool AP_RangeFinder_LeddarVu8::parse_byte(uint8_t b, bool &valid_reading, uint16
return false; return false;
} }
#endif #endif // AP_RANGEFINDER_LEDDARVU8_ENABLED

View File

@ -4,7 +4,7 @@
#include "AP_RangeFinder_Backend_Serial.h" #include "AP_RangeFinder_Backend_Serial.h"
#ifndef AP_RANGEFINDER_LEDDARVU8_ENABLED #ifndef AP_RANGEFINDER_LEDDARVU8_ENABLED
#define AP_RANGEFINDER_LEDDARVU8_ENABLED 1 #define AP_RANGEFINDER_LEDDARVU8_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
#endif #endif
#if AP_RANGEFINDER_LEDDARVU8_ENABLED #if AP_RANGEFINDER_LEDDARVU8_ENABLED
@ -97,4 +97,4 @@ private:
uint32_t last_distance_request_ms; // system time of last request to sensor to send distances uint32_t last_distance_request_ms; // system time of last request to sensor to send distances
}; };
#endif #endif // AP_RANGEFINDER_LEDDARVU8_ENABLED

View File

@ -13,6 +13,9 @@
along with this program. If not, see <http://www.gnu.org/licenses/>. along with this program. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include "AP_RangeFinder_LightWareI2C.h" #include "AP_RangeFinder_LightWareI2C.h"
#if AP_RANGEFINDER_LWI2C_ENABLED
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_HAL/utility/sparse-endian.h> #include <AP_HAL/utility/sparse-endian.h>
@ -500,3 +503,5 @@ bool AP_RangeFinder_LightWareI2C::sf20_wait_on_reply(uint8_t *rx_two_byte)
} }
return false; return false;
} }
#endif // AP_RANGEFINDER_LWI2C_ENABLED

View File

@ -2,6 +2,13 @@
#include "AP_RangeFinder.h" #include "AP_RangeFinder.h"
#include "AP_RangeFinder_Backend.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> #include <AP_HAL/I2CDevice.h>
#define NUM_SF20_DATA_STREAMS 1 #define NUM_SF20_DATA_STREAMS 1
@ -58,3 +65,5 @@ private:
void data_log(uint16_t *val); void data_log(uint16_t *val);
AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev; AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev;
}; };
#endif // AP_RANGEFINDER_LWI2C_ENABLED

View File

@ -15,6 +15,8 @@
#include "AP_RangeFinder_LightWareSerial.h" #include "AP_RangeFinder_LightWareSerial.h"
#if AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <ctype.h> #include <ctype.h>
@ -149,3 +151,5 @@ bool AP_RangeFinder_LightWareSerial::is_lost_signal_distance(int16_t distance_cm
} }
return false; return false;
} }
#endif

View File

@ -3,6 +3,12 @@
#include "AP_RangeFinder.h" #include "AP_RangeFinder.h"
#include "AP_RangeFinder_Backend_Serial.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 class AP_RangeFinder_LightWareSerial : public AP_RangeFinder_Backend_Serial
{ {
@ -43,3 +49,5 @@ private:
bool no_signal = false; bool no_signal = false;
}; };
#endif // AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED

View File

@ -14,6 +14,9 @@
*/ */
#include "AP_RangeFinder_MAVLink.h" #include "AP_RangeFinder_MAVLink.h"
#if AP_RANGEFINDER_MAVLINK_ENABLED
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
/* /*
@ -73,3 +76,5 @@ void AP_RangeFinder_MAVLink::update(void)
update_status(); update_status();
} }
} }
#endif

View File

@ -3,6 +3,12 @@
#include "AP_RangeFinder.h" #include "AP_RangeFinder.h"
#include "AP_RangeFinder_Backend.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 // Data timeout
#define AP_RANGEFINDER_MAVLINK_TIMEOUT_MS 500 #define AP_RANGEFINDER_MAVLINK_TIMEOUT_MS 500
@ -45,3 +51,5 @@ private:
MAV_DISTANCE_SENSOR sensor_type = MAV_DISTANCE_SENSOR_UNKNOWN; MAV_DISTANCE_SENSOR sensor_type = MAV_DISTANCE_SENSOR_UNKNOWN;
}; };
#endif

View File

@ -23,6 +23,8 @@
*/ */
#include "AP_RangeFinder_MaxsonarI2CXL.h" #include "AP_RangeFinder_MaxsonarI2CXL.h"
#if AP_RANGEFINDER_MAXSONARI2CXL_ENABLED
#include <utility> #include <utility>
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
@ -151,3 +153,5 @@ void AP_RangeFinder_MaxsonarI2CXL::update(void)
set_status(RangeFinder::Status::NoData); set_status(RangeFinder::Status::NoData);
} }
} }
#endif // AP_RANGEFINDER_MAXSONARI2CXL_ENABLED

View File

@ -2,6 +2,13 @@
#include "AP_RangeFinder.h" #include "AP_RangeFinder.h"
#include "AP_RangeFinder_Backend.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> #include <AP_HAL/I2CDevice.h>
#define AP_RANGE_FINDER_MAXSONARI2CXL_DEFAULT_ADDR 0x70 #define AP_RANGE_FINDER_MAXSONARI2CXL_DEFAULT_ADDR 0x70
@ -41,3 +48,5 @@ private:
bool get_reading(uint16_t &reading_cm); bool get_reading(uint16_t &reading_cm);
AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev; AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev;
}; };
#endif // AP_RANGEFINDER_MAXSONARI2CXL_ENABLED

View File

@ -17,6 +17,8 @@
#include "AP_RangeFinder_MaxsonarSerialLV.h" #include "AP_RangeFinder_MaxsonarSerialLV.h"
#if AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <ctype.h> #include <ctype.h>
@ -68,3 +70,5 @@ bool AP_RangeFinder_MaxsonarSerialLV::get_reading(float &reading_m)
return true; return true;
} }
#endif // AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED

View File

@ -3,6 +3,12 @@
#include "AP_RangeFinder.h" #include "AP_RangeFinder.h"
#include "AP_RangeFinder_Backend_Serial.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 class AP_RangeFinder_MaxsonarSerialLV : public AP_RangeFinder_Backend_Serial
{ {
@ -25,3 +31,5 @@ private:
char linebuf[10]; char linebuf[10];
uint8_t linebuf_len = 0; uint8_t linebuf_len = 0;
}; };
#endif // AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED

View File

@ -15,6 +15,8 @@
#include "AP_RangeFinder_NMEA.h" #include "AP_RangeFinder_NMEA.h"
#if AP_RANGEFINDER_NMEA_ENABLED
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <ctype.h> #include <ctype.h>
@ -187,3 +189,5 @@ bool AP_RangeFinder_NMEA::decode_latest_term()
return false; return false;
} }
#endif // AP_RANGEFINDER_NMEA_ENABLED

View File

@ -18,6 +18,12 @@
#include "AP_RangeFinder.h" #include "AP_RangeFinder.h"
#include "AP_RangeFinder_Backend_Serial.h" #include "AP_RangeFinder_Backend_Serial.h"
#ifndef AP_RANGEFINDER_NMEA_ENABLED
#define AP_RANGEFINDER_NMEA_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
#endif
#if AP_RANGEFINDER_NMEA_ENABLED
class AP_RangeFinder_NMEA : public AP_RangeFinder_Backend_Serial class AP_RangeFinder_NMEA : public AP_RangeFinder_Backend_Serial
{ {
@ -72,3 +78,5 @@ private:
sentence_types _sentence_type; // the sentence type currently being processed sentence_types _sentence_type; // the sentence type currently being processed
bool _sentence_done; // true if this sentence has already been decoded bool _sentence_done; // true if this sentence has already been decoded
}; };
#endif // AP_RANGEFINDER_NMEA_ENABLED

View File

@ -15,6 +15,8 @@
#include "AP_RangeFinder_PWM.h" #include "AP_RangeFinder_PWM.h"
#if AP_RANGEFINDER_PWM_ENABLED
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <GCS_MAVLink/GCS.h> #include <GCS_MAVLink/GCS.h>
@ -130,3 +132,5 @@ void AP_RangeFinder_PWM::update(void)
bool AP_RangeFinder_PWM::out_of_range(void) const { bool AP_RangeFinder_PWM::out_of_range(void) const {
return params.powersave_range > 0 && estimated_terrain_height > params.powersave_range; return params.powersave_range > 0 && estimated_terrain_height > params.powersave_range;
} }
#endif // AP_RANGEFINDER_PWM_ENABLED

View File

@ -17,6 +17,14 @@
#include "AP_RangeFinder.h" #include "AP_RangeFinder.h"
#include "AP_RangeFinder_Backend.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
#if AP_RANGEFINDER_PWM_ENABLED
class AP_RangeFinder_PWM : public AP_RangeFinder_Backend class AP_RangeFinder_PWM : public AP_RangeFinder_Backend
{ {
public: public:
@ -58,3 +66,5 @@ private:
bool was_out_of_range = -1; // this odd initialisation ensures we transition to new state bool was_out_of_range = -1; // this odd initialisation ensures we transition to new state
}; };
#endif // AP_RANGEFINDER_PWM_ENABLED

View File

@ -14,6 +14,8 @@
*/ */
#include "AP_RangeFinder_PulsedLightLRF.h" #include "AP_RangeFinder_PulsedLightLRF.h"
#if AP_RANGEFINDER_PULSEDLIGHTLRF_ENABLED
#include <utility> #include <utility>
#include <stdio.h> #include <stdio.h>
@ -218,3 +220,4 @@ failed:
return false; return false;
} }
#endif // AP_RANGEFINDER_PULSEDLIGHTLRF_ENABLED

View File

@ -2,6 +2,13 @@
#include "AP_RangeFinder.h" #include "AP_RangeFinder.h"
#include "AP_RangeFinder_Backend.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> #include <AP_HAL/I2CDevice.h>
/* Connection diagram /* Connection diagram
@ -57,3 +64,5 @@ private:
enum { PHASE_MEASURE, PHASE_COLLECT } phase; enum { PHASE_MEASURE, PHASE_COLLECT } phase;
}; };
#endif // AP_RANGEFINDER_PULSEDLIGHTLRF_ENABLED

View File

@ -12,15 +12,12 @@
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>. along with this program. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include "AP_RangeFinder_SITL.h" #include "AP_RangeFinder_SITL.h"
#if AP_SIM_RANGEFINDER_ENABLED #if AP_RANGEFINDER_SIM_ENABLED
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
extern const AP_HAL::HAL& hal;
/* /*
constructor - registers instance at top RangeFinder driver constructor - registers instance at top RangeFinder driver
*/ */
@ -50,5 +47,4 @@ void AP_RangeFinder_SITL::update(void)
update_status(); update_status();
} }
#endif // AP_SIM_RANGEFINDER_ENABLED #endif // AP_RANGEFINDER_SIM_ENABLED

View File

@ -16,13 +16,13 @@
#include <AP_BoardConfig/AP_BoardConfig.h> #include <AP_BoardConfig/AP_BoardConfig.h>
#ifndef AP_SIM_RANGEFINDER_ENABLED #include "AP_RangeFinder_Backend.h"
#define AP_SIM_RANGEFINDER_ENABLED (AP_SIM_ENABLED && !defined(HAL_BUILD_AP_PERIPH))
#ifndef AP_RANGEFINDER_SIM_ENABLED
#define AP_RANGEFINDER_SIM_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED)
#endif #endif
#if AP_SIM_RANGEFINDER_ENABLED #if AP_RANGEFINDER_SIM_ENABLED
#include "AP_RangeFinder_Backend.h"
#include <SITL/SITL.h> #include <SITL/SITL.h>
@ -47,4 +47,4 @@ private:
}; };
#endif // AP_SIM_RANGEFINDER_ENABLED #endif // AP_RANGEFINDER_SIM_ENABLED

View File

@ -17,6 +17,8 @@
*/ */
#include "AP_RangeFinder_TeraRangerI2C.h" #include "AP_RangeFinder_TeraRangerI2C.h"
#if AP_RANGEFINDER_TRI2C_ENABLED
#include <utility> #include <utility>
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_Math/crc.h> #include <AP_Math/crc.h>
@ -189,3 +191,5 @@ void AP_RangeFinder_TeraRangerI2C::update(void)
set_status(RangeFinder::Status::NoData); set_status(RangeFinder::Status::NoData);
} }
} }
#endif // AP_RANGEFINDER_TRI2C_ENABLED

View File

@ -2,6 +2,13 @@
#include "AP_RangeFinder.h" #include "AP_RangeFinder.h"
#include "AP_RangeFinder_Backend.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> #include <AP_HAL/I2CDevice.h>
class AP_RangeFinder_TeraRangerI2C : public AP_RangeFinder_Backend class AP_RangeFinder_TeraRangerI2C : public AP_RangeFinder_Backend
@ -40,3 +47,5 @@ private:
uint32_t count; uint32_t count;
} accum; } accum;
}; };
#endif // AP_RANGEFINDER_TRI2C_ENABLED

View File

@ -1,9 +1,8 @@
#include <AP_HAL/AP_HAL.h>
#if HAL_CANMANAGER_ENABLED
#include "AP_RangeFinder_UAVCAN.h" #include "AP_RangeFinder_UAVCAN.h"
#if AP_RANGEFINDER_UAVCAN_ENABLED
#include <AP_HAL/AP_HAL.h>
#include <AP_CANManager/AP_CANManager.h> #include <AP_CANManager/AP_CANManager.h>
#include <AP_UAVCAN/AP_UAVCAN.h> #include <AP_UAVCAN/AP_UAVCAN.h>
@ -173,5 +172,4 @@ void AP_RangeFinder_UAVCAN::handle_measurement(AP_UAVCAN* ap_uavcan, uint8_t nod
} }
} }
#endif // HAL_CANMANAGER_ENABLED #endif // AP_RANGEFINDER_UAVCAN_ENABLED

View File

@ -2,7 +2,12 @@
#include "AP_RangeFinder_Backend.h" #include "AP_RangeFinder_Backend.h"
#if HAL_CANMANAGER_ENABLED #ifndef AP_RANGEFINDER_UAVCAN_ENABLED
#define AP_RANGEFINDER_UAVCAN_ENABLED (HAL_CANMANAGER_ENABLED && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED)
#endif
#if AP_RANGEFINDER_UAVCAN_ENABLED
#include <AP_UAVCAN/AP_UAVCAN.h> #include <AP_UAVCAN/AP_UAVCAN.h>
class MeasurementCb; class MeasurementCb;
@ -34,4 +39,4 @@ private:
bool new_data; bool new_data;
MAV_DISTANCE_SENSOR _sensor_type; MAV_DISTANCE_SENSOR _sensor_type;
}; };
#endif //HAL_CANMANAGER_ENABLED #endif // AP_RANGEFINDER_UAVCAN_ENABLED

View File

@ -1,7 +1,8 @@
#include <AP_HAL/AP_HAL.h>
#include "AP_RangeFinder_USD1_CAN.h" #include "AP_RangeFinder_USD1_CAN.h"
#if HAL_MAX_CAN_PROTOCOL_DRIVERS #if AP_RANGEFINDER_USD1_CAN_ENABLED
#include <AP_HAL/AP_HAL.h>
/* /*
constructor constructor
@ -39,4 +40,4 @@ void AP_RangeFinder_USD1_CAN::handle_frame(AP_HAL::CANFrame &frame)
_distance_count++; _distance_count++;
} }
#endif // HAL_MAX_CAN_PROTOCOL_DRIVERS #endif // AP_RANGEFINDER_USD1_CAN_ENABLED

View File

@ -3,7 +3,11 @@
#include "AP_RangeFinder_Backend.h" #include "AP_RangeFinder_Backend.h"
#include <AP_CANManager/AP_CANSensor.h> #include <AP_CANManager/AP_CANSensor.h>
#if HAL_MAX_CAN_PROTOCOL_DRIVERS #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 AP_RangeFinder_USD1_CAN : public CANSensor, public AP_RangeFinder_Backend { class AP_RangeFinder_USD1_CAN : public CANSensor, public AP_RangeFinder_Backend {
public: public:
@ -22,5 +26,5 @@ private:
float _distance_sum; float _distance_sum;
uint32_t _distance_count; uint32_t _distance_count;
}; };
#endif //HAL_MAX_CAN_PROTOCOL_DRIVERS
#endif // AP_RANGEFINDER_USD1_CAN_ENABLED

View File

@ -13,15 +13,15 @@
along with this program. If not, see <http://www.gnu.org/licenses/>. along with this program. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include <AP_HAL/AP_HAL.h>
#include "AP_RangeFinder_USD1_Serial.h" #include "AP_RangeFinder_USD1_Serial.h"
#if AP_RANGEFINDER_USD1_SERIAL_ENABLED
#include <ctype.h> #include <ctype.h>
#define USD1_HDR 254 // Header Byte from USD1_Serial (0xFE) #define USD1_HDR 254 // Header Byte from USD1_Serial (0xFE)
#define USD1_HDR_V0 72 // Header Byte for beta V0 of USD1_Serial (0x48) #define USD1_HDR_V0 72 // Header Byte for beta V0 of USD1_Serial (0x48)
extern const AP_HAL::HAL& hal;
/* /*
detect USD1_Serial Firmware Version detect USD1_Serial Firmware Version
*/ */
@ -173,3 +173,5 @@ bool AP_RangeFinder_USD1_Serial::get_reading(float &reading_m)
return true; return true;
} }
#endif // AP_RANGEFINDER_USD1_SERIAL_ENABLED

View File

@ -3,6 +3,12 @@
#include "AP_RangeFinder.h" #include "AP_RangeFinder.h"
#include "AP_RangeFinder_Backend_Serial.h" #include "AP_RangeFinder_Backend_Serial.h"
#ifndef AP_RANGEFINDER_USD1_SERIAL_ENABLED
#define AP_RANGEFINDER_USD1_SERIAL_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
#endif
#if AP_RANGEFINDER_USD1_SERIAL_ENABLED
class AP_RangeFinder_USD1_Serial : public AP_RangeFinder_Backend_Serial class AP_RangeFinder_USD1_Serial : public AP_RangeFinder_Backend_Serial
{ {
@ -37,3 +43,5 @@ private:
uint8_t _header; uint8_t _header;
uint8_t _version; uint8_t _version;
}; };
#endif // AP_RANGEFINDER_USD1_SERIAL_ENABLED

View File

@ -20,6 +20,8 @@
*/ */
#include "AP_RangeFinder_VL53L0X.h" #include "AP_RangeFinder_VL53L0X.h"
#if AP_RANGEFINDER_VL53L0X_ENABLED
#include <utility> #include <utility>
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
@ -780,3 +782,5 @@ void AP_RangeFinder_VL53L0X::timer(void)
counter++; counter++;
} }
} }
#endif // AP_RANGEFINDER_VL53L0X_ENABLED

View File

@ -4,6 +4,12 @@
#include "AP_RangeFinder_Backend.h" #include "AP_RangeFinder_Backend.h"
#include <AP_HAL/I2CDevice.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 class AP_RangeFinder_VL53L0X : public AP_RangeFinder_Backend
{ {
@ -80,3 +86,5 @@ private:
uint32_t sum_mm; uint32_t sum_mm;
uint32_t counter; uint32_t counter;
}; };
#endif // AP_RANGEFINDER_VL53L0X_ENABLED

View File

@ -20,6 +20,8 @@
*/ */
#include "AP_RangeFinder_VL53L1X.h" #include "AP_RangeFinder_VL53L1X.h"
#if AP_RANGEFINDER_VL53L1X_ENABLED
#include <utility> #include <utility>
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
@ -578,3 +580,5 @@ void AP_RangeFinder_VL53L1X::update(void)
set_status(RangeFinder::Status::NoData); set_status(RangeFinder::Status::NoData);
} }
} }
#endif // AP_RANGEFINDER_VL53L1X_ENABLED

View File

@ -2,6 +2,13 @@
#include "AP_RangeFinder.h" #include "AP_RangeFinder.h"
#include "AP_RangeFinder_Backend.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> #include <AP_HAL/I2CDevice.h>
class AP_RangeFinder_VL53L1X : public AP_RangeFinder_Backend class AP_RangeFinder_VL53L1X : public AP_RangeFinder_Backend
@ -1293,3 +1300,5 @@ private:
uint32_t calcMacroPeriod(uint8_t vcsel_period) const; uint32_t calcMacroPeriod(uint8_t vcsel_period) const;
bool setupManualCalibration(void); bool setupManualCalibration(void);
}; };
#endif // AP_RANGEFINDER_VL53L1X_ENABLED

View File

@ -15,6 +15,8 @@
#include "AP_RangeFinder_Wasp.h" #include "AP_RangeFinder_Wasp.h"
#if AP_RANGEFINDER_WASP_ENABLED
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <ctype.h> #include <ctype.h>
@ -247,3 +249,4 @@ void AP_RangeFinder_Wasp::parse_response(void) {
} }
} }
#endif // AP_RANGEFINDER_WASP_ENABLED

View File

@ -3,6 +3,12 @@
#include "AP_RangeFinder.h" #include "AP_RangeFinder.h"
#include "AP_RangeFinder_Backend_Serial.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 // WASP 200 LRF
// http://www.attolloengineering.com/wasp-200-lrf.html // http://www.attolloengineering.com/wasp-200-lrf.html
@ -59,3 +65,5 @@ private:
AP_Int16 thr; AP_Int16 thr;
AP_Int8 baud; AP_Int8 baud;
}; };
#endif

View File

@ -18,12 +18,15 @@
* *
*/ */
#include "AP_RangeFinder_analog.h"
#if AP_RANGEFINDER_ANALOG_ENABLED
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_Common/AP_Common.h> #include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h> #include <AP_Math/AP_Math.h>
#include "AP_RangeFinder.h" #include "AP_RangeFinder.h"
#include "AP_RangeFinder_Params.h" #include "AP_RangeFinder_Params.h"
#include "AP_RangeFinder_analog.h"
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
@ -118,3 +121,4 @@ void AP_RangeFinder_analog::update(void)
update_status(); update_status();
} }
#endif // AP_RANGEFINDER_ANALOG_ENABLED

View File

@ -4,6 +4,12 @@
#include "AP_RangeFinder_Backend.h" #include "AP_RangeFinder_Backend.h"
#include "AP_RangeFinder_Params.h" #include "AP_RangeFinder_Params.h"
#ifndef AP_RANGEFINDER_ANALOG_ENABLED
#define AP_RANGEFINDER_ANALOG_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
#endif
#if AP_RANGEFINDER_ANALOG_ENABLED
class AP_RangeFinder_analog : public AP_RangeFinder_Backend class AP_RangeFinder_analog : public AP_RangeFinder_Backend
{ {
public: public:
@ -28,3 +34,5 @@ private:
AP_HAL::AnalogSource *source; AP_HAL::AnalogSource *source;
}; };
#endif