AP_HAL_ChibiOS: cleanup ifdefs for SLCAN enable
This commit is contained in:
parent
6b3c10f0e7
commit
15e4641e51
@ -119,7 +119,7 @@ inline void handleInterrupt(uavcan::uint8_t iface_index, uavcan::uint8_t line_in
|
||||
} // namespace
|
||||
|
||||
uint32_t CanIface::FDCANMessageRAMOffset_ = 0;
|
||||
#if !HAL_MINIMIZE_FEATURES
|
||||
#if AP_UAVCAN_SLCAN_ENABLED
|
||||
SLCANRouter CanIface::_slcan_router;
|
||||
#endif
|
||||
|
||||
@ -695,7 +695,7 @@ bool CanIface::readRxFIFO(uavcan::uint8_t fifo_index)
|
||||
* Store with timeout into the FIFO buffer and signal update event
|
||||
*/
|
||||
rx_queue_.push(frame, utc_usec, 0);
|
||||
#if !HAL_MINIMIZE_FEATURES
|
||||
#if AP_UAVCAN_SLCAN_ENABLED
|
||||
_slcan_router.route_frame_to_slcan(this, frame, utc_usec);
|
||||
#endif
|
||||
return true;
|
||||
|
@ -85,7 +85,7 @@ struct CanRxItem {
|
||||
*/
|
||||
class CanIface : public uavcan::ICanIface, uavcan::Noncopyable
|
||||
{
|
||||
#if !HAL_MINIMIZE_FEATURES
|
||||
#if AP_UAVCAN_SLCAN_ENABLED
|
||||
friend class ::SLCANRouter;
|
||||
static SLCANRouter _slcan_router;
|
||||
#endif
|
||||
@ -279,7 +279,7 @@ public:
|
||||
return can_;
|
||||
}
|
||||
|
||||
#if !HAL_MINIMIZE_FEATURES
|
||||
#if AP_UAVCAN_SLCAN_ENABLED
|
||||
static SLCANRouter &slcan_router() { return _slcan_router; }
|
||||
#endif
|
||||
};
|
||||
|
@ -87,7 +87,7 @@ struct CanRxItem {
|
||||
*/
|
||||
class CanIface : public uavcan::ICanIface, uavcan::Noncopyable {
|
||||
|
||||
#if !HAL_MINIMIZE_FEATURES
|
||||
#if AP_UAVCAN_SLCAN_ENABLED
|
||||
friend class ::SLCANRouter;
|
||||
static SLCANRouter _slcan_router;
|
||||
#endif
|
||||
@ -285,7 +285,7 @@ public:
|
||||
{
|
||||
return uavcan::uint8_t(peak_tx_mailbox_index_ + 1);
|
||||
}
|
||||
#if !HAL_MINIMIZE_FEATURES
|
||||
#if AP_UAVCAN_SLCAN_ENABLED
|
||||
static SLCANRouter &slcan_router() { return _slcan_router; }
|
||||
#endif
|
||||
};
|
||||
|
@ -17,7 +17,7 @@
|
||||
|
||||
#include "CANSerialRouter.h"
|
||||
|
||||
#if HAL_WITH_UAVCAN && !HAL_MINIMIZE_FEATURES
|
||||
#if AP_UAVCAN_SLCAN_ENABLED
|
||||
#include <AP_SerialManager/AP_SerialManager.h>
|
||||
#include <AP_BoardConfig/AP_BoardConfig_CAN.h>
|
||||
|
||||
|
@ -19,7 +19,7 @@
|
||||
|
||||
#include "AP_HAL_ChibiOS.h"
|
||||
|
||||
#if HAL_WITH_UAVCAN && !HAL_MINIMIZE_FEATURES
|
||||
#if AP_UAVCAN_SLCAN_ENABLED
|
||||
#include "CAN.h"
|
||||
#include <AP_UAVCAN/AP_UAVCAN_SLCAN.h>
|
||||
|
||||
@ -65,4 +65,5 @@ public:
|
||||
|
||||
};
|
||||
|
||||
#endif
|
||||
#endif // AP_UAVCAN_SLCAN_ENABLED
|
||||
|
||||
|
@ -138,7 +138,7 @@ inline void handleRxInterrupt(uavcan::uint8_t iface_index, uavcan::uint8_t fifo_
|
||||
}
|
||||
|
||||
} // namespace
|
||||
#if !HAL_MINIMIZE_FEATURES
|
||||
#if AP_UAVCAN_SLCAN_ENABLED
|
||||
SLCANRouter CanIface::_slcan_router;
|
||||
#endif
|
||||
/*
|
||||
@ -763,7 +763,7 @@ void CanIface::handleRxInterrupt(uavcan::uint8_t fifo_index, uavcan::uint64_t ut
|
||||
* Store with timeout into the FIFO buffer and signal update event
|
||||
*/
|
||||
rx_queue_.push(frame, utc_usec, 0);
|
||||
#if !HAL_MINIMIZE_FEATURES
|
||||
#if AP_UAVCAN_SLCAN_ENABLED
|
||||
_slcan_router.route_frame_to_slcan(this, frame, utc_usec);
|
||||
#endif
|
||||
had_activity_ = true;
|
||||
|
Loading…
Reference in New Issue
Block a user