AP_RangeFinder: use AP_CANManager library
This commit is contained in:
parent
0fcf0b4564
commit
6ef85dd7eb
@ -518,7 +518,7 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
|
||||
}
|
||||
break;
|
||||
|
||||
#if HAL_WITH_UAVCAN
|
||||
#if HAL_ENABLE_LIBUAVCAN_DRIVERS
|
||||
case Type::UAVCAN:
|
||||
/*
|
||||
the UAVCAN driver gets created when we first receive a
|
||||
|
@ -1,10 +1,10 @@
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if HAL_WITH_UAVCAN
|
||||
#if HAL_ENABLE_LIBUAVCAN_DRIVERS
|
||||
|
||||
#include "AP_RangeFinder_UAVCAN.h"
|
||||
|
||||
#include <AP_BoardConfig/AP_BoardConfig_CAN.h>
|
||||
#include <AP_CANManager/AP_CANManager.h>
|
||||
#include <AP_UAVCAN/AP_UAVCAN.h>
|
||||
|
||||
#include <uavcan/equipment/range_sensor/Measurement.hpp>
|
||||
@ -180,5 +180,5 @@ void AP_RangeFinder_UAVCAN::handle_measurement(AP_UAVCAN* ap_uavcan, uint8_t nod
|
||||
}
|
||||
}
|
||||
|
||||
#endif // HAL_WITH_UAVCAN
|
||||
#endif // HAL_ENABLE_LIBUAVCAN_DRIVERS
|
||||
|
||||
|
@ -2,7 +2,7 @@
|
||||
|
||||
#include "AP_RangeFinder_Backend.h"
|
||||
|
||||
#if HAL_WITH_UAVCAN
|
||||
#if HAL_ENABLE_LIBUAVCAN_DRIVERS
|
||||
#include <AP_UAVCAN/AP_UAVCAN.h>
|
||||
|
||||
class MeasurementCb;
|
||||
@ -33,4 +33,4 @@ private:
|
||||
bool new_data;
|
||||
MAV_DISTANCE_SENSOR _sensor_type;
|
||||
};
|
||||
#endif //HAL_WITH_UAVCAN
|
||||
#endif //HAL_ENABLE_LIBUAVCAN_DRIVERS
|
||||
|
Loading…
Reference in New Issue
Block a user