mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: disable SLCAN for minimize feature enabled
This commit is contained in:
parent
816c339e4d
commit
7a2668ae1a
|
@ -17,7 +17,7 @@
|
|||
|
||||
#include "CANSerialRouter.h"
|
||||
|
||||
#if HAL_WITH_UAVCAN
|
||||
#if HAL_WITH_UAVCAN && !HAL_MINIMIZE_FEATURES
|
||||
#include <AP_SerialManager/AP_SerialManager.h>
|
||||
#include <AP_BoardConfig/AP_BoardConfig_CAN.h>
|
||||
SLCANRouter* SLCANRouter::_singleton = nullptr;
|
||||
|
|
|
@ -19,7 +19,7 @@
|
|||
|
||||
#include "AP_HAL_ChibiOS.h"
|
||||
|
||||
#if HAL_WITH_UAVCAN
|
||||
#if HAL_WITH_UAVCAN && !HAL_MINIMIZE_FEATURES
|
||||
#include "CAN.h"
|
||||
#include <AP_UAVCAN/AP_UAVCAN_SLCAN.h>
|
||||
|
||||
|
|
|
@ -759,8 +759,9 @@ 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
|
||||
slcan_router().route_frame_to_slcan(this, frame, utc_usec);
|
||||
|
||||
#endif
|
||||
had_activity_ = true;
|
||||
update_event_.signalFromInterrupt();
|
||||
|
||||
|
|
Loading…
Reference in New Issue