mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_RangeFinder: Use HAL_CANMANAGER_ENABLED instead of HAL_ENABLE_LIBUAVCAN_DRIVERS
This commit is contained in:
parent
6d8972e63b
commit
0795225475
@ -540,7 +540,7 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
|
||||
break;
|
||||
|
||||
case Type::UAVCAN:
|
||||
#if HAL_ENABLE_LIBUAVCAN_DRIVERS
|
||||
#if HAL_CANMANAGER_ENABLED
|
||||
/*
|
||||
the UAVCAN driver gets created when we first receive a
|
||||
measurement. We take the instance slot now, even if we don't
|
||||
|
@ -1,6 +1,6 @@
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if HAL_ENABLE_LIBUAVCAN_DRIVERS
|
||||
#if HAL_CANMANAGER_ENABLED
|
||||
|
||||
#include "AP_RangeFinder_UAVCAN.h"
|
||||
|
||||
@ -180,5 +180,5 @@ void AP_RangeFinder_UAVCAN::handle_measurement(AP_UAVCAN* ap_uavcan, uint8_t nod
|
||||
}
|
||||
}
|
||||
|
||||
#endif // HAL_ENABLE_LIBUAVCAN_DRIVERS
|
||||
#endif // HAL_CANMANAGER_ENABLED
|
||||
|
||||
|
@ -2,7 +2,7 @@
|
||||
|
||||
#include "AP_RangeFinder_Backend.h"
|
||||
|
||||
#if HAL_ENABLE_LIBUAVCAN_DRIVERS
|
||||
#if HAL_CANMANAGER_ENABLED
|
||||
#include <AP_UAVCAN/AP_UAVCAN.h>
|
||||
|
||||
class MeasurementCb;
|
||||
@ -33,4 +33,4 @@ private:
|
||||
bool new_data;
|
||||
MAV_DISTANCE_SENSOR _sensor_type;
|
||||
};
|
||||
#endif //HAL_ENABLE_LIBUAVCAN_DRIVERS
|
||||
#endif //HAL_CANMANAGER_ENABLED
|
||||
|
Loading…
Reference in New Issue
Block a user