Go to the documentation of this file.
15 #ifndef UAVCAN_LPC11C24_RX_QUEUE_LEN
16 # define UAVCAN_LPC11C24_RX_QUEUE_LEN 8
19 #if UAVCAN_LPC11C24_RX_QUEUE_LEN > 254
20 # error UAVCAN_LPC11C24_RX_QUEUE_LEN is too large
38 constexpr
unsigned NumberOfMessageObjects = 32;
39 constexpr
unsigned NumberOfTxMessageObjects = 1;
40 constexpr
unsigned NumberOfRxMessageObjects = NumberOfMessageObjects - NumberOfTxMessageObjects;
41 constexpr
unsigned TxMessageObjectNumber = 1;
52 volatile bool tx_pending =
false;
57 volatile bool tx_abort_on_error =
false;
67 volatile bool had_activity =
false;
128 unsigned getLength()
const {
return len_; }
136 struct BitTimingSettings
141 bool isValid()
const {
return canbtr != 0; }
153 case 1000000:
return BitTimingSettings{ 0, 0x0505 };
154 case 500000:
return BitTimingSettings{ 0, 0x1c05 };
155 case 250000:
return BitTimingSettings{ 0, 0x1c0b };
156 case 125000:
return BitTimingSettings{ 0, 0x1c17 };
157 case 100000:
return BitTimingSettings{ 0, 0x1c1d };
158 default:
return BitTimingSettings{ 0, 0 };
163 return BitTimingSettings{ 0, 0 };
187 for (
auto bitrate : BitRatesToTry)
190 const auto bit_timings = computeBitTimings(bitrate);
191 if (!bit_timings.isValid())
233 bool match_detected =
false;
236 if (idle_callback !=
nullptr)
245 match_detected =
true;
277 auto bit_timings = computeBitTimings(bitrate);
278 if (!bit_timings.isValid())
286 tx_abort_on_error =
false;
288 last_irq_utc_timestamp = 0;
289 had_activity =
false;
333 return rx_queue.getLength() > 0;
345 const bool ret = had_activity;
346 had_activity =
false;
353 return rx_queue.getOverflowCount();
398 msgobj.
msgobj = TxMessageObjectNumber;
412 if (rx_queue.getLength() == 0)
417 rx_queue.pop(out_frame, ts_utc);
441 #if defined(UAVCAN_LPC11C24_USE_WFE) && UAVCAN_LPC11C24_USE_WFE
491 if (num_configs == 0)
494 msg_obj.msgobj = NumberOfTxMessageObjects + 1;
498 msg_obj.msgobj = NumberOfTxMessageObjects + 2;
501 else if (num_configs <= NumberOfRxMessageObjects)
504 for (
unsigned i = 0; i < num_configs; i++)
506 auto&
f = filter_configs[i];
514 for (
unsigned i = 0; i < NumberOfRxMessageObjects; i++)
517 msg_obj.msgobj =
std::uint8_t(i + 1U + NumberOfTxMessageObjects);
549 return NumberOfRxMessageObjects;
554 return (iface_index == 0) ? this :
nullptr;
575 msg_obj.msgobj = msg_obj_num;
601 rx_queue.push(
frame, last_irq_utc_timestamp);
620 if ((error_info != 0) && (error_cnt < 0xFFFFFFFFUL))
626 if (tx_pending && tx_abort_on_error)
629 tx_abort_on_error =
false;
static constexpr std::uint32_t CNTL_SIE
uavcan::uint16_t getNumFilters() const override
static const uint32_t MaskStdID
static const uint32_t FlagEFF
Extended frame format.
std::uint32_t overflow_cnt_
void canTxCallback(std::uint8_t msg_obj_num)
uavcan::MonotonicTime getMonotonic()
Implicitly convertible to/from uavcan.Timestamp.
void canErrorCallback(std::uint32_t error_info)
static constexpr std::uint32_t TEST_SILENT
union uavcan_lpc11c24::c_can::MsgIfaceType::@168 CMDMSK
static constexpr std::uint32_t STAT_BOFF
uavcan::int16_t configureFilters(const uavcan::CanFilterConfig *filter_configs, uavcan::uint16_t num_configs) override
static MonotonicDuration fromMSec(int64_t ms)
bool isInBusOffState() const
static constexpr std::uint32_t CNTL_CCE
uavcan::int16_t send(const uavcan::CanFrame &frame, uavcan::MonotonicTime tx_deadline, uavcan::CanIOFlags flags) override
void canRxCallback(std::uint8_t msg_obj_num)
std::uint64_t getUtcUSecFromCanInterrupt()
uint8_t dlc
Data Length Code.
static const CanIOFlags CanIOFlagLoopback
uint32_t id
CAN ID with flags (above)
bool isErrorFrame() const
static constexpr std::uint32_t IF_MCTRL_TXRQST
__STATIC_INLINE void NVIC_DisableIRQ(IRQn_Type IRQn)
Disable External Interrupt.
STATIC INLINE void Chip_Clock_EnablePeriphClock(CHIP_SYSCTL_CLOCK_T clk)
Enable a system or peripheral clock.
__STATIC_INLINE void NVIC_EnableIRQ(IRQn_Type IRQn)
Enable External Interrupt.
static constexpr std::uint32_t CNTL_TEST
struct CCAN_MSG_OBJ CCAN_MSG_OBJ_T
static UtcTime fromUSec(uint64_t us)
static const uint32_t MaskExtID
static constexpr std::uint32_t IF_CMDMSK_W_WR_RD
bool isRemoteTransmissionRequest() const
uavcan::ICanIface * getIface(uavcan::uint8_t iface_index) override
uavcan::int16_t select(uavcan::CanSelectMasks &inout_masks, const uavcan::CanFrame *(&)[uavcan::MaxCanIfaces], uavcan::MonotonicTime blocking_deadline) override
int init(uavcan::uint32_t bitrate)
uint32_t Chip_Clock_GetSystemClockRate(void)
Return system clock rate.
uavcan::uint8_t getNumIfaces() const override
#define UAVCAN_LPC11C24_RX_QUEUE_LEN
Item buf_[UAVCAN_LPC11C24_RX_QUEUE_LEN]
static constexpr std::uint32_t STAT_LEC_SHIFT
static constexpr std::uint32_t CNTL_INIT
UAVCAN_EXPORT OutputIt copy(InputIt first, InputIt last, OutputIt result)
static const CanIOFlags CanIOFlagAbortOnError
uavcan::int16_t receive(uavcan::CanFrame &out_frame, uavcan::MonotonicTime &out_ts_monotonic, uavcan::UtcTime &out_ts_utc, uavcan::CanIOFlags &out_flags) override
uavcan::uint32_t getRxQueueOverflowCount() const
static constexpr std::uint32_t STAT_LEC_MASK
uavcan::uint64_t getErrorCount() const override
static const uint32_t FlagRTR
Remote transmission request.
static uavcan::uint32_t detectBitRate(void(*idle_callback)()=nullptr)