53 #define BIT_2_TO_15_MASK 0x0000fffc 109 }
else if (hw ==
MCAN1) {
165 #if (SAMV71B || SAME70B || SAMV70B) 254 if (module_inst->
hw ==
MCAN0) {
257 }
else if (module_inst->
hw ==
MCAN1) {
279 module_inst->
hw = hw;
282 pmc_enable_upll_clock();
313 uint32_t gclk_mcan_value;
314 uint32_t mcan_nbtp_nbrp_value;
315 uint32_t mcan_nbtp_nsgw_value = 3, mcan_nbtp_ntseg1_value = 10, mcan_nbtp_ntseg2_value = 7;
317 gclk_mcan_value = 20000000;
320 mcan_nbtp_nbrp_value = gclk_mcan_value / baudrate / (3 + mcan_nbtp_ntseg1_value + mcan_nbtp_ntseg2_value)-1;
321 #if (SAMV71B || SAME70B || SAMV70B) 342 uint32_t gclk_mcan_fd_value;
343 uint32_t mcan_fd_dbtp_dbrp_value;
344 uint32_t mcan_fd_dbtp_dsgw_value = 3, mcan_fd_dbtp_dtseg1_value = 9, mcan_fd_dbtp_dtseg2_value = 3;
348 mcan_fd_dbtp_dbrp_value = gclk_mcan_fd_value / baudrate / (3 + mcan_fd_dbtp_dtseg1_value + mcan_fd_dbtp_dtseg2_value);
349 #if (SAMV71B || SAME70B || SAMV70B) 400 #if (SAMV71B || SAME70B || SAMV70B) 421 #if (SAMV71B || SAME70B || SAMV70B) 555 if (module_inst->
hw ==
MCAN0) {
558 }
else if (module_inst->
hw ==
MCAN1) {
578 if (module_inst->
hw ==
MCAN0) {
582 }
else if (module_inst->
hw ==
MCAN1) {
603 if (module_inst->
hw ==
MCAN0) {
606 }
else if (module_inst->
hw ==
MCAN1) {
626 if (module_inst->
hw ==
MCAN0) {
629 }
else if (module_inst->
hw ==
MCAN1) {
649 if (module_inst->
hw ==
MCAN0) {
652 }
else if (module_inst->
hw ==
MCAN1) {
673 if (module_inst->
hw ==
MCAN0) {
680 }
else if (module_inst->
hw ==
MCAN1) {
704 if (module_inst->
hw ==
MCAN0) {
708 }
else if (module_inst->
hw ==
MCAN1) {
#define CONF_MCAN1_RX_FIFO_1_NUM
#define MCAN_CCCR_DAR
(MCAN_CCCR) Disable Automatic Retransmission (read/write, write protection)
enum mcan_nonmatching_frames_action nonmatching_frames_action_standard
static void _mcan_enable_peripheral_clock(struct mcan_module *const module_inst)
enable can module clock.
__IO uint32_t MCAN_XIDAM
(Mcan Offset: 0x90) Extended ID AND Mask Register
#define MCAN_FBTP_FSJW(value)
MCAN transfer event FIFO element structure.
#define MCAN_TDCR_TDCO(value)
MCAN receive element structure for FIFO 0.
#define MCAN_CCCR_CME_ISO11898_1
(MCAN_CCCR) CAN operation according to ISO11898-1 enabled
static struct mcan_tx_event_element mcan0_tx_event_fifo[CONF_MCAN0_TX_EVENT_FIFO]
MCAN receive element structure for buffer.
#define CONF_MCAN_NBTP_NBRP_VALUE
bool automatic_retransmission
static struct mcan_rx_element_fifo_0 mcan0_rx_fifo_0[CONF_MCAN0_RX_FIFO_0_NUM]
#define MCAN_BTP_TSEG1(value)
#define CONF_MCAN0_RX_FIFO_1_NUM
#define CONF_MCAN0_TX_BUFFER_NUM
#define MCAN_NBTP_NTSEG2(value)
MCAN transfer element structure.
#define CONF_MCAN0_RX_BUFFER_NUM
#define MCAN_RXF0C_F0WM(value)
static struct mcan_rx_element_fifo_0 mcan1_rx_fifo_0[CONF_MCAN1_RX_FIFO_0_NUM]
void pmc_enable_pck(uint32_t ul_id)
Enable the specified programmable clock.
#define MCAN_TXBC_TFQM
(MCAN_TXBC) Tx FIFO/Queue Mode
__IO uint32_t MCAN_TXBCIE
(Mcan Offset: 0xE4) Transmit Buffer Cancellation Finished Interrupt Enable Register ...
#define CONF_MCAN0_RX_EXTENDED_ID_FILTER_NUM
#define CONF_MCAN1_RX_EXTENDED_ID_FILTER_NUM
MCAN extended message ID filter element structure.
__IO MCAN_TX_EVENT_ELEMENT_E0_Type E0
#define MCAN_DBTP_DTSEG2(value)
#define MCAN1
(MCAN1 ) Base Address
__IO MCAN_TX_EVENT_ELEMENT_E1_Type E1
#define MCAN_DBTP_DSJW(value)
#define MCAN_RXESC_RBDS(value)
__IO MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F0_Type F0
#define CONF_MCAN_NBTP_NTSEG2_VALUE
#define MCAN_RXESC_F0DS(value)
#define MCAN_CCCR_CCE
(MCAN_CCCR) Configuration Change Enable (read/write, write protection)
#define MCAN_TSCC_TSS_TCP_INC
(MCAN_TSCC) Timestamp counter value incremented according to TCP
static struct mcan_tx_event_element mcan1_tx_event_fifo[CONF_MCAN1_TX_EVENT_FIFO]
#define MCAN_CCCR_CMR(value)
enum status_code mcan_get_tx_event_fifo_element(struct mcan_module *const module_inst, struct mcan_tx_event_element *tx_event_element, uint32_t index)
set FIFO transmit buffer element .
uint8_t delay_compensation_offset
#define MCAN_GFC_ANFS(value)
MCAN receive element structure for FIFO 1.
#define MCAN_TXBC_TFQS(value)
#define CONF_MCAN_FBTP_FTSEG1_VALUE
void mcan_disable_bus_monitor_mode(struct mcan_module *const module_inst)
disable bus monitor mode of mcan module.
uint32_t pmc_enable_periph_clk(uint32_t ul_id)
Enable the specified peripheral clock.
#define MCAN_CCCR_CSA
(MCAN_CCCR) Clock Stop Acknowledge (read-only)
#define MCAN_RXF1C_F1OM
(MCAN_RXF1C) FIFO 1 Operation Mode
SAM Control Area Network (MCAN) Low Level Driver.
__IO uint32_t MCAN_TEST
(Mcan Offset: 0x10) Test Register
#define MCAN_CCCR_FDOE
(MCAN_CCCR) CAN FD Operation Enable (read/write, write protection)
#define MCAN_TOCC_TOP(value)
#define MCAN_CCCR_CME(value)
#define MCAN_CCCR_CSR
(MCAN_CCCR) Clock Stop Request (read/write)
#define MCAN_FBTP_FBRP(value)
#define MCAN_TXEFC_EFWM(value)
void mcan_stop(struct mcan_module *const module_inst)
stop mcan module when bus off occurs
__IO uint32_t MCAN_RXF0C
(Mcan Offset: 0xA0) Receive FIFO 0 Configuration Register
#define CONF_MCAN_NBTP_NTSEG1_VALUE
static struct mcan_extended_message_filter_element mcan0_rx_extended_filter[CONF_MCAN0_RX_EXTENDED_ID_FILTER_NUM]
#define MCAN_FBTP_TDC_ENABLED
(MCAN_FBTP) Transceiver Delay Compensation enabled.
#define MCAN_TDCR_TDCF(value)
#define MCAN_NBTP_NBRP(value)
void mcan_enable_test_mode(struct mcan_module *const module_inst)
enable test mode of mcan module.
void pmc_disable_pck(uint32_t ul_id)
Disable the specified programmable clock.
bool remote_frames_standard_reject
void mcan_enable_restricted_operation_mode(struct mcan_module *const module_inst)
enable restricted mode of mcan module.
void mcan_start(struct mcan_module *const module_inst)
start can module after initialization.
#define MCAN_CCCR_MON
(MCAN_CCCR) Bus Monitoring Mode (read/write, write protection against '1')
__IO uint32_t MCAN_FBTP
(Mcan Offset: 0x0C) Fast Bit Timing and Prescaler Register
#define CONF_MCAN_ELEMENT_DATA_SIZE
#define MCAN_TEST_LBCK
(MCAN_TEST) Loop Back Mode (read/write)
#define CONF_MCAN1_RX_STANDARD_ID_FILTER_NUM
MCAN configuration structure.
#define MCAN_FBTP_FTSEG2(value)
#define CONF_MCAN_FBTP_FSJW_VALUE
void mcan_disable_sleep_mode(struct mcan_module *const module_inst)
disable sleep mode of mcan module.
__IO MCAN_TX_ELEMENT_T0_Type T0
#define MCAN_CCCR_TXP
(MCAN_CCCR) Transmit Pause (read/write, write protection)
__IO uint32_t MCAN_TXBC
(Mcan Offset: 0xC0) Transmit Buffer Configuration Register
static struct mcan_extended_message_filter_element mcan1_rx_extended_filter[CONF_MCAN1_RX_EXTENDED_ID_FILTER_NUM]
static void _mcan_message_memory_init(Mcan *hw)
initialize MCAN memory .
static uint32_t sysclk_get_peripheral_hz(void)
Retrieves the current rate in Hz of the peripheral clocks.
#define MCAN_TSCC_TCP(value)
__IO uint32_t MCAN_ILE
(Mcan Offset: 0x5C) Interrupt Line Enable Register
#define MCAN_CCCR_ASM
(MCAN_CCCR) Restricted Operation Mode (read/write, write protection against '1')
COMPILER_ALIGNED(32)
Buffer to receive data.
static struct mcan_rx_element_buffer mcan0_rx_buffer[CONF_MCAN0_RX_BUFFER_NUM]
#define CONF_MCAN1_TX_EVENT_FIFO
__IO uint32_t MCAN_TSCC
(Mcan Offset: 0x20) Timestamp Counter Configuration Register
#define MCAN_ILE_EINT0
(MCAN_ILE) Enable Interrupt Line 0
__IO uint32_t MCAN_CCCR
(Mcan Offset: 0x18) CC Control Register
#define CONF_MCAN_NBTP_NSJW_VALUE
#define MCAN_GFC_RRFE
(MCAN_GFC) Reject Remote Frames Extended
#define CONF_MCAN_FBTP_FTSEG2_VALUE
#define CONF_MCAN1_TX_FIFO_QUEUE_NUM
enum status_code mcan_set_rx_extended_filter(struct mcan_module *const module_inst, struct mcan_extended_message_filter_element *et_filter, uint32_t index)
set extended receive CAN ID.
enum status_code mcan_get_rx_buffer_element(struct mcan_module *const module_inst, struct mcan_rx_element_buffer *rx_element, uint32_t index)
get dedicated rx buffer element .
#define MCAN_RXF0C_F0OM
(MCAN_RXF0C) FIFO 0 Operation Mode
#define MCAN_NBTP_NTSEG1(value)
#define MCAN_FBTP_TDCO(value)
#define CONF_MCAN0_RX_FIFO_0_NUM
void mcan_disable_test_mode(struct mcan_module *const module_inst)
disable test mode of mcan module.
#define MCAN_TXBC_NDTB(value)
#define MCAN_DBTP_DBRP(value)
void mcan_fd_set_baudrate(Mcan *hw, uint32_t baudrate)
Set MCAN_FD baudrate.
#define CONF_MCAN0_RX_STANDARD_ID_FILTER_NUM
#define MCAN_BTP_BRP(value)
#define MCAN_BTP_TSEG2(value)
#define MCAN_TXEFC_EFS(value)
#define MCAN_GFC_RRFS
(MCAN_GFC) Reject Remote Frames Standard
#define MCAN_SIDFC_LSS(value)
#define MCAN_RXF1C_F1S(value)
#define PMC_PCK_PRES(value)
#define MCAN_CCCR_TEST
(MCAN_CCCR) Test Mode Enable (read/write, write protection against '1')
__IO uint32_t MCAN_TOCC
(Mcan Offset: 0x28) Timeout Counter Configuration Register
#define MCAN_ILE_EINT1
(MCAN_ILE) Enable Interrupt Line 1
#define CONF_MCAN0_TX_FIFO_QUEUE_NUM
static struct mcan_rx_element_fifo_1 mcan0_rx_fifo_1[CONF_MCAN0_RX_FIFO_1_NUM]
__IO MCAN_TX_ELEMENT_T1_Type T1
uint8_t timestamp_prescaler
#define MCAN_RXF1C_F1WM(value)
enum mcan_nonmatching_frames_action nonmatching_frames_action_extended
#define MCAN_DBTP_TDC_ENABLED
(MCAN_DBTP) Transmitter Delay Compensation enabled.
bool remote_frames_extended_reject
__IO uint32_t MCAN_BTP
(Mcan Offset: 0x1C) Bit Timing and Prescaler Register
static struct mcan_rx_element_buffer mcan1_rx_buffer[CONF_MCAN1_RX_BUFFER_NUM]
#define MCAN0
(MCAN0 ) Base Address
uint8_t watchdog_configuration
#define MCAN_CCCR_INIT
(MCAN_CCCR) Initialization (read/write)
static struct mcan_standard_message_filter_element mcan0_rx_standard_filter[CONF_MCAN0_RX_STANDARD_ID_FILTER_NUM]
uint8_t rx_fifo_1_watermark
enum status_code mcan_get_rx_fifo_0_element(struct mcan_module *const module_inst, struct mcan_rx_element_fifo_0 *rx_element, uint32_t index)
get FIFO rx buffer element .
void mcan_enable_sleep_mode(struct mcan_module *const module_inst)
enable sleep mode of mcan module.
void mcan_enable_fd_mode(struct mcan_module *const module_inst)
switch mcan module into fd mode.
#define MCAN_CCCR_BRSE
(MCAN_CCCR) Bit Rate Switching Enable (read/write, write protection)
#define ID_MCAN1
MCAN Controller 1 (MCAN1)
enum mcan_timeout_mode timeout_mode
void mcan_enable_bus_monitor_mode(struct mcan_module *const module_inst)
enable bus monitor mode of mcan module.
static struct mcan_standard_message_filter_element mcan1_rx_standard_filter[CONF_MCAN1_RX_STANDARD_ID_FILTER_NUM]
#define CONF_MCAN1_TX_BUFFER_NUM
static struct mcan_tx_element mcan1_tx_buffer[CONF_MCAN1_TX_BUFFER_NUM+CONF_MCAN1_TX_FIFO_QUEUE_NUM]
uint32_t extended_id_mask
enum status_code mcan_get_rx_fifo_1_element(struct mcan_module *const module_inst, struct mcan_rx_element_fifo_1 *rx_element, uint32_t index)
get FIFO rx buffer element .
#define MCAN_NBTP_NSJW(value)
void mcan_disable_fd_mode(struct mcan_module *const module_inst)
disable fd mode of mcan module.
static void _mcan_set_configuration(Mcan *hw, struct mcan_config *config)
set default configuration when initialization.
void mcan_set_baudrate(Mcan *hw, uint32_t baudrate)
Set MCAN baudrate.
__IO uint32_t MCAN_TXBTIE
(Mcan Offset: 0xE0) Transmit Buffer Transmission Interrupt Enable Register
#define MCAN_RXF0C_F0S(value)
uint8_t rx_fifo_0_watermark
#define MCAN_XIDFC_LSE(value)
uint8_t tx_event_fifo_watermark
#define CONF_MCAN1_RX_FIFO_0_NUM
#define MCAN_RWD_WDC(value)
__IO uint32_t MCAN_RXF1C
(Mcan Offset: 0xB0) Receive FIFO 1 Configuration Register
#define MCAN_GFC_ANFE(value)
__IO uint32_t MCAN_GFC
(Mcan Offset: 0x80) Global Filter Configuration Register
#define MCAN_DBTP_DTSEG1(value)
MCAN standard message ID filter element structure.
#define ID_MCAN0
MCAN Controller 0 (MCAN0)
#define MCAN_BTP_SJW(value)
#define CONF_MCAN1_RX_BUFFER_NUM
__IO MCAN_STANDARD_MESSAGE_FILTER_ELEMENT_S0_Type S0
#define MCAN_FBTP_FTSEG1(value)
__IO MCAN_EXTENDED_MESSAGE_FILTER_ELEMENT_F1_Type F1
enum status_code mcan_set_tx_buffer_element(struct mcan_module *const module_inst, struct mcan_tx_element *tx_element, uint32_t index)
set dedicated transmit buffer element .
void mcan_disable_restricted_operation_mode(struct mcan_module *const module_inst)
disable restricted mode of mcan module.
static struct mcan_rx_element_fifo_1 mcan1_rx_fifo_1[CONF_MCAN1_RX_FIFO_1_NUM]
__IO uint32_t MCAN_RWD
(Mcan Offset: 0x14) RAM Watchdog Register
#define Assert(expr)
This macro is used to test fatal errors.
void mcan_init(struct mcan_module *const module_inst, Mcan *hw, struct mcan_config *config)
initialize can module.
MCAN software device instance structure.
__IO uint32_t MCAN_TXEFC
(Mcan Offset: 0xF0) Transmit Event FIFO Configuration Register
#define CONF_MCAN_FBTP_FBRP_VALUE
#define MCAN_TXESC_TBDS(value)
enum status_code mcan_set_rx_standard_filter(struct mcan_module *const module_inst, struct mcan_standard_message_filter_element *sd_filter, uint32_t index)
set standard receive CAN ID.
uint8_t data[CONF_MCAN_ELEMENT_DATA_SIZE]
static struct mcan_tx_element mcan0_tx_buffer[CONF_MCAN0_TX_BUFFER_NUM+CONF_MCAN0_TX_FIFO_QUEUE_NUM]
#define CONF_MCAN0_TX_EVENT_FIFO
#define MCAN_RXESC_F1DS(value)