diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Backend_CAN.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Backend_CAN.cpp
index ebc60dc2d1..69e43afc48 100644
--- a/libraries/AP_RangeFinder/AP_RangeFinder_Backend_CAN.cpp
+++ b/libraries/AP_RangeFinder/AP_RangeFinder_Backend_CAN.cpp
@@ -13,11 +13,13 @@
along with this program. If not, see .
*/
+#include "AP_RangeFinder_config.h"
+
+#if AP_RANGEFINDER_BACKEND_CAN_ENABLED
+
#include
#include "AP_RangeFinder_Backend_CAN.h"
-#if HAL_MAX_CAN_PROTOCOL_DRIVERS
-
const AP_Param::GroupInfo AP_RangeFinder_Backend_CAN::var_info[] = {
// @Param: RECV_ID
@@ -87,4 +89,4 @@ bool AP_RangeFinder_Backend_CAN::is_correct_id(uint32_t id) const
return true;
}
-#endif // HAL_MAX_CAN_PROTOCOL_DRIVERS
+#endif // AP_RANGEFINDER_BACKEND_CAN_ENABLED
diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Backend_CAN.h b/libraries/AP_RangeFinder/AP_RangeFinder_Backend_CAN.h
index 96d62aa94d..5f91509419 100644
--- a/libraries/AP_RangeFinder/AP_RangeFinder_Backend_CAN.h
+++ b/libraries/AP_RangeFinder/AP_RangeFinder_Backend_CAN.h
@@ -1,9 +1,10 @@
#pragma once
+#include "AP_RangeFinder_config.h"
+
+#if AP_RANGEFINDER_BACKEND_CAN_ENABLED
+
#include "AP_RangeFinder_Backend.h"
-
-#if HAL_MAX_CAN_PROTOCOL_DRIVERS
-
#include
#include
@@ -61,4 +62,4 @@ private:
uint32_t _distance_count;
};
-#endif // HAL_MAX_CAN_PROTOCOL_DRIVERS
+#endif // AP_RANGEFINDER_BACKEND_CAN_ENABLED
diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_config.h b/libraries/AP_RangeFinder/AP_RangeFinder_config.h
index 69d1f6e537..1f5407adaf 100644
--- a/libraries/AP_RangeFinder/AP_RangeFinder_config.h
+++ b/libraries/AP_RangeFinder/AP_RangeFinder_config.h
@@ -15,6 +15,10 @@
#define AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED AP_RANGEFINDER_ENABLED
#endif
+#ifndef AP_RANGEFINDER_BACKEND_CAN_ENABLED
+#define AP_RANGEFINDER_BACKEND_CAN_ENABLED AP_RANGEFINDER_ENABLED && HAL_MAX_CAN_PROTOCOL_DRIVERS
+#endif
+
#ifndef AP_RANGEFINDER_ANALOG_ENABLED
#define AP_RANGEFINDER_ANALOG_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED
#endif
@@ -148,7 +152,7 @@
#endif
#ifndef AP_RANGEFINDER_TOFSENSEP_CAN_ENABLED
-#define AP_RANGEFINDER_TOFSENSEP_CAN_ENABLED (HAL_MAX_CAN_PROTOCOL_DRIVERS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED)
+#define AP_RANGEFINDER_TOFSENSEP_CAN_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED && AP_RANGEFINDER_BACKEND_CAN_ENABLED
#endif
#ifndef AP_RANGEFINDER_TOFSENSEF_I2C_ENABLED
@@ -160,7 +164,7 @@
#endif
#ifndef AP_RANGEFINDER_USD1_CAN_ENABLED
-#define AP_RANGEFINDER_USD1_CAN_ENABLED (HAL_MAX_CAN_PROTOCOL_DRIVERS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED)
+#define AP_RANGEFINDER_USD1_CAN_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED && AP_RANGEFINDER_BACKEND_CAN_ENABLED
#endif
#ifndef AP_RANGEFINDER_USD1_SERIAL_ENABLED