Macros | Functions | Variables
mcan.c File Reference

SAM Control Area Network (MCAN) Low Level Driver. More...

#include "mcan.h"
#include "pmc.h"
#include <string.h>
#include <sysclk.h>
Include dependency graph for mcan.c:

Go to the source code of this file.

Macros

#define BIT_2_TO_15_MASK   0x0000fffc
 
#define PMC_PCK_5   5
 

Functions

static void _mcan_enable_peripheral_clock (struct mcan_module *const module_inst)
 enable can module clock. More...
 
static void _mcan_message_memory_init (Mcan *hw)
 initialize MCAN memory . More...
 
static void _mcan_set_configuration (Mcan *hw, struct mcan_config *config)
 set default configuration when initialization. More...
 
void mcan_disable_bus_monitor_mode (struct mcan_module *const module_inst)
 disable bus monitor mode of mcan module. More...
 
void mcan_disable_fd_mode (struct mcan_module *const module_inst)
 disable fd mode of mcan module. More...
 
void mcan_disable_restricted_operation_mode (struct mcan_module *const module_inst)
 disable restricted mode of mcan module. More...
 
void mcan_disable_sleep_mode (struct mcan_module *const module_inst)
 disable sleep mode of mcan module. More...
 
void mcan_disable_test_mode (struct mcan_module *const module_inst)
 disable test mode of mcan module. More...
 
void mcan_enable_bus_monitor_mode (struct mcan_module *const module_inst)
 enable bus monitor mode of mcan module. More...
 
void mcan_enable_fd_mode (struct mcan_module *const module_inst)
 switch mcan module into fd mode. More...
 
void mcan_enable_restricted_operation_mode (struct mcan_module *const module_inst)
 enable restricted mode of mcan module. More...
 
void mcan_enable_sleep_mode (struct mcan_module *const module_inst)
 enable sleep mode of mcan module. More...
 
void mcan_enable_test_mode (struct mcan_module *const module_inst)
 enable test mode of mcan module. More...
 
void mcan_fd_set_baudrate (Mcan *hw, uint32_t baudrate)
 Set MCAN_FD baudrate. More...
 
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 . More...
 
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 . More...
 
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 . More...
 
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 . More...
 
void mcan_init (struct mcan_module *const module_inst, Mcan *hw, struct mcan_config *config)
 initialize can module. More...
 
void mcan_set_baudrate (Mcan *hw, uint32_t baudrate)
 Set MCAN baudrate. More...
 
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. More...
 
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. More...
 
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 . More...
 
void mcan_start (struct mcan_module *const module_inst)
 start can module after initialization. More...
 
void mcan_stop (struct mcan_module *const module_inst)
 stop mcan module when bus off occurs More...
 

Variables

static struct mcan_rx_element_buffer mcan0_rx_buffer [CONF_MCAN0_RX_BUFFER_NUM]
 
static struct mcan_extended_message_filter_element mcan0_rx_extended_filter [CONF_MCAN0_RX_EXTENDED_ID_FILTER_NUM]
 
static struct mcan_rx_element_fifo_0 mcan0_rx_fifo_0 [CONF_MCAN0_RX_FIFO_0_NUM]
 
static struct mcan_rx_element_fifo_1 mcan0_rx_fifo_1 [CONF_MCAN0_RX_FIFO_1_NUM]
 
static struct mcan_standard_message_filter_element mcan0_rx_standard_filter [CONF_MCAN0_RX_STANDARD_ID_FILTER_NUM]
 
static struct mcan_tx_element mcan0_tx_buffer [CONF_MCAN0_TX_BUFFER_NUM+CONF_MCAN0_TX_FIFO_QUEUE_NUM]
 
static struct mcan_tx_event_element mcan0_tx_event_fifo [CONF_MCAN0_TX_EVENT_FIFO]
 
static struct mcan_rx_element_buffer mcan1_rx_buffer [CONF_MCAN1_RX_BUFFER_NUM]
 
static struct mcan_extended_message_filter_element mcan1_rx_extended_filter [CONF_MCAN1_RX_EXTENDED_ID_FILTER_NUM]
 
static struct mcan_rx_element_fifo_0 mcan1_rx_fifo_0 [CONF_MCAN1_RX_FIFO_0_NUM]
 
static struct mcan_rx_element_fifo_1 mcan1_rx_fifo_1 [CONF_MCAN1_RX_FIFO_1_NUM]
 
static struct mcan_standard_message_filter_element mcan1_rx_standard_filter [CONF_MCAN1_RX_STANDARD_ID_FILTER_NUM]
 
static struct mcan_tx_element mcan1_tx_buffer [CONF_MCAN1_TX_BUFFER_NUM+CONF_MCAN1_TX_FIFO_QUEUE_NUM]
 
static struct mcan_tx_event_element mcan1_tx_event_fifo [CONF_MCAN1_TX_EVENT_FIFO]
 

Detailed Description

SAM Control Area Network (MCAN) Low Level Driver.

Copyright (c) 2015-2018 Microchip Technology Inc. and its subsidiaries.

Definition in file mcan.c.

Macro Definition Documentation

◆ BIT_2_TO_15_MASK

#define BIT_2_TO_15_MASK   0x0000fffc

Definition at line 53 of file mcan.c.

◆ PMC_PCK_5

#define PMC_PCK_5   5

Definition at line 51 of file mcan.c.

Function Documentation

◆ _mcan_enable_peripheral_clock()

static void _mcan_enable_peripheral_clock ( struct mcan_module *const  module_inst)
static

enable can module clock.

Parameters
module_instMCAN instance

Definition at line 252 of file mcan.c.

◆ _mcan_message_memory_init()

static void _mcan_message_memory_init ( Mcan hw)
static

initialize MCAN memory .

Parameters
hwBase address of the MCAN

The data size in conf_mcan.h should be 8/12/16/20/24/32/48/64, The corresponding setting value in register is 0/1//2/3/4/5/6/7. To simplify the calculation, seperate to two group 8/12/16/20/24 which increased with 4 and 32/48/64 which increased with 16.

Definition at line 92 of file mcan.c.

◆ _mcan_set_configuration()

static void _mcan_set_configuration ( Mcan hw,
struct mcan_config config 
)
static

set default configuration when initialization.

Parameters
hwBase address of the MCAN
configdefault configuration parameters.

Definition at line 163 of file mcan.c.

Variable Documentation

◆ mcan0_rx_buffer

struct mcan_rx_element_buffer mcan0_rx_buffer[CONF_MCAN0_RX_BUFFER_NUM]
static

Definition at line 57 of file mcan.c.

◆ mcan0_rx_extended_filter

Definition at line 69 of file mcan.c.

◆ mcan0_rx_fifo_0

struct mcan_rx_element_fifo_0 mcan0_rx_fifo_0[CONF_MCAN0_RX_FIFO_0_NUM]
static

Definition at line 59 of file mcan.c.

◆ mcan0_rx_fifo_1

struct mcan_rx_element_fifo_1 mcan0_rx_fifo_1[CONF_MCAN0_RX_FIFO_1_NUM]
static

Definition at line 61 of file mcan.c.

◆ mcan0_rx_standard_filter

Definition at line 67 of file mcan.c.

◆ mcan0_tx_buffer

Definition at line 63 of file mcan.c.

◆ mcan0_tx_event_fifo

struct mcan_tx_event_element mcan0_tx_event_fifo[CONF_MCAN0_TX_EVENT_FIFO]
static

Definition at line 65 of file mcan.c.

◆ mcan1_rx_buffer

struct mcan_rx_element_buffer mcan1_rx_buffer[CONF_MCAN1_RX_BUFFER_NUM]
static

Definition at line 72 of file mcan.c.

◆ mcan1_rx_extended_filter

Definition at line 84 of file mcan.c.

◆ mcan1_rx_fifo_0

struct mcan_rx_element_fifo_0 mcan1_rx_fifo_0[CONF_MCAN1_RX_FIFO_0_NUM]
static

Definition at line 74 of file mcan.c.

◆ mcan1_rx_fifo_1

struct mcan_rx_element_fifo_1 mcan1_rx_fifo_1[CONF_MCAN1_RX_FIFO_1_NUM]
static

Definition at line 76 of file mcan.c.

◆ mcan1_rx_standard_filter

Definition at line 82 of file mcan.c.

◆ mcan1_tx_buffer

Definition at line 78 of file mcan.c.

◆ mcan1_tx_event_fifo

struct mcan_tx_event_element mcan1_tx_event_fifo[CONF_MCAN1_TX_EVENT_FIFO]
static

Definition at line 80 of file mcan.c.



inertial_sense_ros
Author(s):
autogenerated on Sat Sep 19 2020 03:19:06