20 #include <nuttx/irq.h> 22 #include <drivers/drv_hrt.h> 24 #include <arch/board/board.h> 26 #include "Scheduler.h" 41 static int can1_irq(
const int irq,
void*);
42 #if CAN_STM32_NUM_IFACES > 1 43 static int can2_irq(
const int irq,
void*);
62 sem_init(&_wait_semaphore, 0, 0);
69 bool BusEvent::wait(uavcan::MonotonicDuration duration)
71 struct hrt_call wait_call;
73 irqstate_t irs = irqsave();
80 sem_init(&_wait_semaphore, 0, 0);
83 hrt_call_after(&wait_call, duration.toUSec(), (hrt_callout) signalFromCallOut,
this);
84 sem_wait(&_wait_semaphore);
86 hrt_cancel(&wait_call);
100 void BusEvent::signalFromCallOut(
BusEvent *sem)
105 void BusEvent::signalFromInterrupt()
108 sem_post(&_wait_semaphore);
111 static void handleTxInterrupt(uint8_t iface_index)
116 for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_DRIVERS; i++) {
117 if (hal.
can_mgr[i] !=
nullptr) {
119 if (iface !=
nullptr) {
127 static void handleRxInterrupt(uint8_t iface_index, uint8_t fifo_index)
132 for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_DRIVERS; i++) {
133 if (hal.
can_mgr[i] !=
nullptr) {
135 if (iface !=
nullptr) {
145 int VRBRAINCAN::computeTimings(
const uint32_t target_bitrate, Timings& out_timings)
147 if (target_bitrate < 1) {
154 const uint32_t pclk = STM32_PCLK1_FREQUENCY;
156 static const uint8_t MaxBS1 = 16;
157 static const uint8_t MaxBS2 = 8;
170 const uint8_t max_quanta_per_bit = (target_bitrate >= 1000000) ? 10 : 17;
172 if (max_quanta_per_bit > (MaxBS1 + MaxBS2)) {
173 if (AP_BoardConfig_CAN::get_can_debug() >= 1) {
174 printf(
"VRBRAINCAN::computeTimings max_quanta_per_bit problem\n\r");
178 static const uint16_t MaxSamplePointLocation = 900;
190 const uint32_t prescaler_bs = pclk / target_bitrate;
195 uint8_t bs1_bs2_sum = uint8_t(max_quanta_per_bit - 1);
197 while ((prescaler_bs % (1 + bs1_bs2_sum)) != 0) {
198 if (bs1_bs2_sum <= 2) {
204 const uint32_t prescaler = prescaler_bs / (1 + bs1_bs2_sum);
205 if ((prescaler < 1U) || (prescaler > 1024U)) {
230 uint16_t sample_point_permill;
233 bs1(0), bs2(0), sample_point_permill(0)
237 BsPair(uint8_t bs1_bs2_sum, uint8_t arg_bs1) :
238 bs1(arg_bs1), bs2(uint8_t(bs1_bs2_sum - bs1)), sample_point_permill(
239 uint16_t(1000 * (1 + bs1) / (1 + bs1 + bs2)))
241 if (bs1_bs2_sum <= arg_bs1) {
242 if (AP_BoardConfig_CAN::get_can_debug() >= 1) {
243 AP_HAL::panic(
"VRBRAINCAN::computeTimings bs1_bs2_sum <= arg_bs1");
250 return (bs1 >= 1) && (bs1 <= MaxBS1) && (bs2 >= 1) && (bs2 <= MaxBS2);
255 BsPair solution(bs1_bs2_sum, uint8_t(((7 * bs1_bs2_sum - 1) + 4) / 8));
257 if (solution.sample_point_permill > MaxSamplePointLocation || !solution.isValid()) {
259 solution = BsPair(bs1_bs2_sum, uint8_t((7 * bs1_bs2_sum - 1) / 8));
261 if (!solution.isValid())
263 printf(
"VRBRAINCAN::computeTimings second solution invalid\n\r");
271 if ((target_bitrate != (pclk / (prescaler * (1 + solution.bs1 + solution.bs2)))) || !solution.isValid()) {
272 if (AP_BoardConfig_CAN::get_can_debug() >= 1) {
273 printf(
"VRBRAINCAN::computeTimings target_bitrate error\n\r");
278 if (AP_BoardConfig_CAN::get_can_debug() >= 2) {
279 printf(
"VRBRAINCAN::computeTimings Timings: quanta/bit: %d, sample point location: %.1f%%\n\r",
280 int(1 + solution.bs1 + solution.bs2),
double(solution.sample_point_permill / 10.0));
283 out_timings.prescaler = uint16_t(prescaler - 1U);
285 out_timings.bs1 = uint8_t(solution.bs1 - 1);
286 out_timings.bs2 = uint8_t(solution.bs2 - 1);
291 int16_t VRBRAINCAN::send(
const uavcan::CanFrame& frame, uavcan::MonotonicTime tx_deadline, uavcan::CanIOFlags flags)
293 if (frame.isErrorFrame() || frame.dlc > 8) {
317 uint8_t txmailbox = 0xFF;
328 peak_tx_mailbox_index_ =
uavcan::max(peak_tx_mailbox_index_, txmailbox);
334 if (frame.isExtended()) {
337 mb.
TIR = ((frame.id & uavcan::CanFrame::MaskStdID) << 21);
340 if (frame.isRemoteTransmissionRequest()) {
346 mb.
TDHR = (uint32_t(frame.data[7]) << 24) | (uint32_t(frame.data[6]) << 16) | (uint32_t(frame.data[5]) << 8)
347 | (uint32_t(frame.data[4]) << 0);
348 mb.
TDLR = (uint32_t(frame.data[3]) << 24) | (uint32_t(frame.data[2]) << 16) | (uint32_t(frame.data[1]) << 8)
349 | (uint32_t(frame.data[0]) << 0);
356 TxItem& txi = pending_tx_[txmailbox];
357 txi.deadline = tx_deadline;
359 txi.loopback = (flags & uavcan::CanIOFlagLoopback) != 0;
360 txi.abort_on_error = (flags & uavcan::CanIOFlagAbortOnError) != 0;
365 int16_t VRBRAINCAN::receive(uavcan::CanFrame& out_frame, uavcan::MonotonicTime& out_ts_monotonic,
366 uavcan::UtcTime& out_ts_utc, uavcan::CanIOFlags& out_flags)
369 uint64_t utc_usec = 0;
372 if (rx_queue_.available() == 0) {
378 out_frame = frm.
frame;
380 out_flags = frm.
flags;
382 out_ts_utc = uavcan::UtcTime::fromUSec(utc_usec);
386 int16_t VRBRAINCAN::configureFilters(
const uavcan::CanFilterConfig* filter_configs, uint16_t num_configs)
388 if (num_configs <= NumFilters) {
394 can_->FMR = (can_->FMR & ~0x00003F00) | static_cast<uint32_t>(NumFilters) << 8;
396 can_->FFA1R = 0x0AAAAAAA;
398 can_->FS1R = 0x7ffffff;
400 const uint8_t filter_start_index = (self_index_ == 0) ? 0 : NumFilters;
402 if (num_configs == 0) {
403 can_->FilterRegister[filter_start_index].FR1 = 0;
404 can_->FilterRegister[filter_start_index].FR2 = 0;
405 can_->FA1R = 1 << filter_start_index;
407 for (uint8_t i = 0; i < NumFilters; i++) {
408 if (i < num_configs) {
412 const uavcan::CanFilterConfig*
const cfg = filter_configs + i;
414 if ((cfg->id & uavcan::CanFrame::FlagEFF) || !(cfg->mask & uavcan::CanFrame::FlagEFF)) {
415 id = (cfg->id & uavcan::CanFrame::MaskExtID) << 3;
416 mask = (cfg->mask & uavcan::CanFrame::MaskExtID) << 3;
419 id = (cfg->id & uavcan::CanFrame::MaskStdID) << 21;
420 mask = (cfg->mask & uavcan::CanFrame::MaskStdID) << 21;
423 if (cfg->id & uavcan::CanFrame::FlagRTR) {
427 if (cfg->mask & uavcan::CanFrame::FlagEFF) {
431 if (cfg->mask & uavcan::CanFrame::FlagRTR) {
435 can_->FilterRegister[filter_start_index + i].FR1 = id;
436 can_->FilterRegister[filter_start_index + i].FR2 = mask;
438 can_->FA1R |= (1 << (filter_start_index + i));
440 can_->FA1R &= ~(1 << (filter_start_index + i));
453 bool VRBRAINCAN::waitMsrINakBitStateChange(
bool target_state)
455 const unsigned Timeout = 1000;
456 for (
unsigned wait_ack = 0; wait_ack < Timeout; wait_ack++) {
458 if (state == target_state) {
479 if (!waitMsrINakBitStateChange(
true)) {
480 if (AP_BoardConfig_CAN::get_can_debug() >= 1) {
481 printf(
"VRBRAINCAN::init MSR INAK not set\n\r");
492 served_aborts_cnt_ = 0;
493 uavcan::fill_n(pending_tx_, NumTxMailboxes, TxItem());
494 peak_tx_mailbox_index_ = 0;
495 had_activity_ =
false;
501 const int timings_res = computeTimings(bitrate, timings);
502 if (timings_res < 0) {
506 if (AP_BoardConfig_CAN::get_can_debug() >= 2) {
507 printf(
"VRBRAINCAN::init Timings: presc=%u sjw=%u bs1=%u bs2=%u\n\r",
unsigned(timings.prescaler),
508 unsigned(timings.sjw),
unsigned(timings.bs1),
unsigned(timings.bs2));
516 can_->BTR = ((timings.sjw & 3U) << 24) | ((timings.bs1 & 15U) << 16) | ((timings.bs2 & 7U) << 20)
517 | (timings.prescaler & 1023U) | ((mode == SilentMode) ?
bxcan::BTR_SILM : 0);
525 if (!waitMsrINakBitStateChange(
false)) {
526 if (AP_BoardConfig_CAN::get_can_debug() >= 1) {
527 printf(
"VRBRAINCAN::init MSR INAK not cleared\n\r");
536 if (self_index_ == 0) {
539 can_->FMR &= 0xFFFFC0F1;
540 can_->FMR |=
static_cast<uint32_t
>(NumFilters) << 8;
545 #if CAN_STM32_NUM_IFACES > 1 546 can_->FS1R = 0x7ffffff;
547 can_->FilterRegister[0].FR1 = 0;
548 can_->FilterRegister[0].FR2 = 0;
549 can_->FilterRegister[NumFilters].FR1 = 0;
550 can_->FilterRegister[NumFilters].FR2 = 0;
551 can_->FA1R = 1 | (1 << NumFilters);
554 can_->FilterRegister[0].FR1 = 0;
555 can_->FilterRegister[0].FR2 = 0;
565 void VRBRAINCAN::handleTxMailboxInterrupt(uint8_t mailbox_index,
bool txok,
const uint64_t utc_usec)
567 if (mailbox_index < NumTxMailboxes) {
569 had_activity_ = had_activity_ || txok;
571 TxItem& txi = pending_tx_[mailbox_index];
573 if (txi.loopback && txok && txi.pending) {
575 frm.
frame = txi.frame;
576 frm.
flags = uavcan::CanIOFlagLoopback;
585 void VRBRAINCAN::handleTxInterrupt(
const uint64_t utc_usec)
591 handleTxMailboxInterrupt(0, txok, utc_usec);
596 handleTxMailboxInterrupt(1, txok, utc_usec);
601 handleTxMailboxInterrupt(2, txok, utc_usec);
604 if(update_event_ !=
nullptr) {
605 update_event_->signalFromInterrupt();
608 pollErrorFlagsFromISR();
611 void VRBRAINCAN::handleRxInterrupt(uint8_t fifo_index, uint64_t utc_usec)
613 if (fifo_index < 2) {
615 volatile uint32_t*
const rfr_reg = (fifo_index == 0) ? &can_->RF0R : &can_->RF1R;
630 uavcan::CanFrame frame;
634 frame.id = uavcan::CanFrame::MaskStdID & (rf.
RIR >> 21);
636 frame.id = uavcan::CanFrame::MaskExtID & (rf.
RIR >> 3);
637 frame.id |= uavcan::CanFrame::FlagEFF;
641 frame.id |= uavcan::CanFrame::FlagRTR;
644 frame.dlc = rf.
RDTR & 15;
646 frame.data[0] = uint8_t(0xFF & (rf.
RDLR >> 0));
647 frame.data[1] = uint8_t(0xFF & (rf.
RDLR >> 8));
648 frame.data[2] = uint8_t(0xFF & (rf.
RDLR >> 16));
649 frame.data[3] = uint8_t(0xFF & (rf.
RDLR >> 24));
650 frame.data[4] = uint8_t(0xFF & (rf.
RDHR >> 0));
651 frame.data[5] = uint8_t(0xFF & (rf.
RDHR >> 8));
652 frame.data[6] = uint8_t(0xFF & (rf.
RDHR >> 16));
653 frame.data[7] = uint8_t(0xFF & (rf.
RDHR >> 24));
666 had_activity_ =
true;
667 if(update_event_ !=
nullptr) {
668 update_event_->signalFromInterrupt();
671 pollErrorFlagsFromISR();
675 void VRBRAINCAN::pollErrorFlagsFromISR()
683 for (
int i = 0; i < NumTxMailboxes; i++) {
684 TxItem& txi = pending_tx_[i];
685 if (txi.pending && txi.abort_on_error) {
686 can_->TSR = TSR_ABRQx[i];
688 served_aborts_cnt_++;
694 void VRBRAINCAN::discardTimedOutTxMailboxes(uavcan::MonotonicTime current_time)
697 for (
int i = 0; i < NumTxMailboxes; i++) {
698 TxItem& txi = pending_tx_[i];
699 if (txi.pending && txi.deadline < current_time) {
700 can_->TSR = TSR_ABRQx[i];
707 bool VRBRAINCAN::canAcceptNewTxFrame(
const uavcan::CanFrame& frame)
const 716 const uint32_t tme = can_->TSR & TME;
732 for (
int mbx = 0; mbx < NumTxMailboxes; mbx++) {
733 if (pending_tx_[mbx].pending && !frame.priorityHigherThan(pending_tx_[mbx].frame)) {
741 bool VRBRAINCAN::isRxBufferEmpty()
const 744 return rx_queue_.available() == 0;
747 uint64_t VRBRAINCAN::getErrorCount()
const 754 unsigned VRBRAINCAN::getRxQueueLength()
const 757 return rx_queue_.available();
760 bool VRBRAINCAN::hadActivity()
763 const bool ret = had_activity_;
764 had_activity_ =
false;
768 bool VRBRAINCAN::begin(uint32_t bitrate)
770 if (
init(bitrate, OperatingMode::NormalMode) == 0) {
774 initialized_ =
false;
781 if (initialized_ && bitrate_ != 0) {
782 init(bitrate_, OperatingMode::NormalMode);
786 bool VRBRAINCAN::is_initialized()
791 int32_t VRBRAINCAN::available()
794 return getRxQueueLength();
800 int32_t VRBRAINCAN::tx_pending()
808 for (
int mbx = 0; mbx < NumTxMailboxes; mbx++) {
809 if (pending_tx_[mbx].pending) {
822 VRBRAINCANManager::VRBRAINCANManager() :
826 uavcan::StaticAssert<(CAN_STM32_RX_QUEUE_SIZE <= VRBRAINCAN::MaxRxQueueCapacity)>::check();
829 _ifaces_out_to_in[i] = UINT8_MAX;
833 uavcan::CanSelectMasks VRBRAINCANManager::makeSelectMasks(
const uavcan::CanFrame* (&pending_tx)[uavcan::MaxCanIfaces])
const 835 uavcan::CanSelectMasks msk;
837 for (uint8_t i = 0; i < _ifaces_num; i++) {
838 if (ifaces[i] !=
nullptr) {
839 if (!ifaces[i]->isRxBufferEmpty()) {
843 if (pending_tx[i] !=
nullptr) {
844 if (ifaces[i]->canAcceptNewTxFrame(*pending_tx[i])) {
854 bool VRBRAINCANManager::hasReadableInterfaces()
const 858 for (uint8_t i = 0; i < _ifaces_num; i++) {
859 if (ifaces[i] !=
nullptr) {
860 ret |= !ifaces[i]->isRxBufferEmpty();
867 int16_t VRBRAINCANManager::select(uavcan::CanSelectMasks& inout_masks,
868 const uavcan::CanFrame* (&pending_tx)[uavcan::MaxCanIfaces],
const uavcan::MonotonicTime blocking_deadline)
870 const uavcan::CanSelectMasks in_masks = inout_masks;
873 for (uint8_t i = 0; i < _ifaces_num; i++) {
874 if (ifaces[i] !=
nullptr) {
875 ifaces[i]->discardTimedOutTxMailboxes(time);
878 ifaces[i]->pollErrorFlagsFromISR();
883 inout_masks = makeSelectMasks(pending_tx);
884 if ((inout_masks.read & in_masks.read) != 0 || (inout_masks.write & in_masks.write) != 0) {
888 (void) update_event_.wait(blocking_deadline - time);
889 inout_masks = makeSelectMasks(pending_tx);
893 void VRBRAINCANManager::initOnce(uint8_t can_number)
897 if (can_number == 0) {
898 modifyreg32(STM32_RCC_APB1ENR, 0, RCC_APB1ENR_CAN1EN);
900 #if CAN_STM32_NUM_IFACES > 1 901 if (can_number == 1) {
902 modifyreg32(STM32_RCC_APB1ENR, 0, RCC_APB1ENR_CAN2EN);
907 if (can_number == 0) {
908 #if defined(GPIO_CAN1_RX) && defined(GPIO_CAN1_TX) 909 stm32_configgpio(GPIO_CAN1_RX);
910 stm32_configgpio(GPIO_CAN1_TX);
912 # error "Need to define GPIO_CAN1_RX/TX" 915 #if CAN_STM32_NUM_IFACES > 1 916 if (can_number == 1) {
917 #if defined(GPIO_CAN2_RX) && defined(GPIO_CAN2_TX) 918 stm32_configgpio(GPIO_CAN2_RX | GPIO_PULLUP);
919 stm32_configgpio(GPIO_CAN2_TX);
921 # error "Need to define GPIO_CAN2_RX/TX" 922 #endif // defined(GPIO_CAN2_RX) && defined(GPIO_CAN2_TX) 924 #endif // CAN_STM32_NUM_IFACES > 1 929 if (can_number == 0) {
930 #if defined(STM32_IRQ_CAN1TX) && defined(STM32_IRQ_CAN1RX0) && defined(STM32_IRQ_CAN1RX1) 935 # error "Need to define STM32_IRQ_CAN1TX/RX0/RX1" 939 #if CAN_STM32_NUM_IFACES > 1 940 if (can_number == 1) {
941 #if defined(STM32_IRQ_CAN2TX) && defined(STM32_IRQ_CAN2RX0) && defined(STM32_IRQ_CAN2RX1) 946 # error "Need to define STM32_IRQ_CAN2TX/RX0/RX1" 947 #endif // defined(STM32_IRQ_CAN2TX) && defined(STM32_IRQ_CAN2RX0) && defined(STM32_IRQ_CAN2RX1) 949 #endif // CAN_STM32_NUM_IFACES > 1 960 if (AP_BoardConfig_CAN::get_can_debug(can_number) >= 2) {
961 printf(
"VRBRAINCANManager::init Bitrate %lu mode %d bus %d\n\r", static_cast<unsigned long>(bitrate),
962 static_cast<int>(mode), static_cast<int>(can_number));
966 if (!initialized_once[can_number]) {
967 initialized_once[can_number] =
true;
969 _ifaces_out_to_in[can_number] = _ifaces_num - 1;
971 if (AP_BoardConfig_CAN::get_can_debug(can_number) >= 2) {
972 printf(
"VRBRAINCANManager::init First initialization bus %d\n\r", static_cast<int>(can_number));
975 initOnce(can_number);
981 if (can_number == 0) {
982 if (AP_BoardConfig_CAN::get_can_debug(0) >= 2) {
983 printf(
"VRBRAINCANManager::init Initing iface 0...\n\r");
985 ifaces[_ifaces_out_to_in[can_number]] = &if0_;
988 #if CAN_STM32_NUM_IFACES > 1 992 if (can_number == 1) {
993 if (AP_BoardConfig_CAN::get_can_debug(1) >= 2) {
994 printf(
"VRBRAINCANManager::init Initing iface 1...\n\r");
996 ifaces[_ifaces_out_to_in[can_number]] = &if1_;
1000 ifaces[_ifaces_out_to_in[can_number]]->set_update_event(&update_event_);
1001 res = ifaces[_ifaces_out_to_in[can_number]]->init(bitrate, mode);
1003 ifaces[_ifaces_out_to_in[can_number]] =
nullptr;
1007 if (AP_BoardConfig_CAN::get_can_debug(can_number) >= 2) {
1008 printf(
"VRBRAINCANManager::init CAN drv init OK, res = %d\n\r", res);
1015 VRBRAINCAN* VRBRAINCANManager::getIface(uint8_t iface_index)
1017 if (iface_index < _ifaces_num) {
1018 return ifaces[iface_index];
1024 VRBRAINCAN* VRBRAINCANManager::getIface_out_to_in(uint8_t iface_index)
1028 if (_ifaces_out_to_in[iface_index] != UINT8_MAX) {
1029 return ifaces[_ifaces_out_to_in[iface_index]];
1036 bool VRBRAINCANManager::hadActivity()
1041 for (uint8_t i = 0; i < _ifaces_num; i++)
1043 if (ifaces[i] !=
nullptr) {
1051 bool VRBRAINCANManager::begin(uint32_t bitrate, uint8_t can_number)
1054 if (
init(bitrate, VRBRAINCAN::OperatingMode::NormalMode, can_number) >= 0) {
1061 bool VRBRAINCANManager::is_initialized()
1063 return initialized_;
1066 void VRBRAINCANManager::initialized(
bool val)
1071 AP_UAVCAN *VRBRAINCANManager::get_UAVCAN(
void)
1076 void VRBRAINCANManager::set_UAVCAN(
AP_UAVCAN *uavcan)
1085 static int can1_irq(
const int irq,
void*)
1087 if (irq == STM32_IRQ_CAN1TX) {
1088 handleTxInterrupt(0);
1089 }
else if (irq == STM32_IRQ_CAN1RX0) {
1090 handleRxInterrupt(0, 0);
1091 }
else if (irq == STM32_IRQ_CAN1RX1) {
1092 handleRxInterrupt(0, 1);
1094 printf(
"can1_irq unhandled");
1099 #if CAN_STM32_NUM_IFACES > 1 1100 static int can2_irq(
const int irq,
void*)
1102 if (irq == STM32_IRQ_CAN2TX) {
1103 handleTxInterrupt(1);
1104 }
else if (irq == STM32_IRQ_CAN2RX0) {
1105 handleRxInterrupt(1, 0);
1106 }
else if (irq == STM32_IRQ_CAN2RX1) {
1107 handleRxInterrupt(1, 1);
1109 printf(
"can2_irq unhandled");
int printf(const char *fmt,...)
constexpr unsigned long TSR_RQCP0
constexpr unsigned long TIR_IDE
uint64_t getUtcUSecFromCanInterrupt()
constexpr unsigned long TIR_RTR
constexpr unsigned long TSR_ABRQ0
constexpr unsigned long TSR_TXOK2
static const int16_t ErrLogic
Internal logic error.
constexpr unsigned long IER_FMPIE0
constexpr unsigned long FMR_FINIT
constexpr unsigned long TIR_TXRQ
static int max(int a, int b)
void handleRxInterrupt(uint8_t fifo_index, uint64_t utc_usec)
constexpr unsigned long TSR_TME2
#define CAN_STM32_RX_QUEUE_SIZE
constexpr unsigned long MCR_RESET
constexpr unsigned long IER_TMEIE
#define CAN_IRQ_ATTACH(irq, handler)
uavcan::MonotonicTime getMonotonic()
constexpr unsigned long MCR_AWUM
constexpr unsigned long MSR_INAK
constexpr unsigned long TSR_RQCP1
constexpr unsigned long TSR_TXOK1
AP_HAL::CANManager ** can_mgr
constexpr unsigned long RFR_RFOM
constexpr unsigned long ESR_LEC_SHIFT
constexpr unsigned long TSR_ABRQ2
constexpr unsigned long RIR_IDE
constexpr unsigned long IER_FMPIE1
constexpr unsigned long RFR_FULL
#define CAN_STM32_NUM_IFACES
constexpr unsigned long TSR_TME0
static const int16_t ErrMsrInakNotSet
INAK bit of the MSR register is not 1.
static const int16_t ErrMsrInakNotCleared
INAK bit of the MSR register is not 0.
constexpr unsigned long RFR_FOVR
static const int16_t ErrInvalidBitRate
Bit rate not supported.
void handleTxInterrupt(uint64_t utc_usec)
uavcan::MonotonicTime getMonotonic()
constexpr unsigned long MCR_ABOM
static const int16_t ErrNotImplemented
Feature not implemented.
BusEvent(VRBRAINCANManager &can_driver)
constexpr unsigned long ESR_LEC_MASK
uint64_t getUtcUSecFromCanInterrupt()
constexpr unsigned long TSR_TXOK0
constexpr unsigned long TSR_RQCP2
static const int16_t ErrFilterNumConfigs
Auto bit rate detection could not be finished.
void init()
Generic board initialization function.
virtual void delay_microseconds(uint16_t us)=0
constexpr unsigned long RFR_FMP_MASK
constexpr unsigned long TSR_ABRQ1
constexpr unsigned long BTR_SILM
constexpr unsigned long MCR_INRQ
constexpr unsigned long TSR_TME1
constexpr unsigned long MCR_SLEEP
void panic(const char *errormsg,...) FMT_PRINTF(1
constexpr unsigned long RIR_RTR
static const int16_t ErrUnsupportedFrame
Frame not supported (e.g. RTR, CAN FD, etc)
AP_HAL::Scheduler * scheduler