drivers: can: add start and stop CAN controller API functions
Up until now, the Zephyr CAN controller drivers set a default bitrate (or timing) specified via devicetree and start the CAN controller in their respective driver initialization functions. This is fine for CAN nodes using only one fixed bitrate, but if the bitrate is set by the user (e.g. via a DIP-switch or other HMI which is very common), the CAN driver will still initialise with the default bitrate/timing at boot and use this until the application has determined the requested bitrate/timing and set it using can_set_bitrate()/can_set_timing(). During this period, the CAN node will potentially destroy valid CAN frames on the CAN bus (which is using the soon-to-be-set-by-the-application bitrate) by sending error frames. This causes interruptions to the ongoing CAN bus traffic when a Zephyr-based CAN node connected to the bus is (re-)booted. Instead, require all configuration (setting bitrate, timing, or mode) to take place when the CAN controller is stopped. This maps nicely to entering "reset mode" (called "configuration mode" or "freeze mode" for some CAN controller implementations) when stopping and exiting this mode when starting the CAN controller. Fixes: #45304 Signed-off-by: Henrik Brix Andersen <hebad@vestas.com>
This commit is contained in:
parent
6d094d0ad5
commit
180cdc105e
30 changed files with 930 additions and 319 deletions
|
@ -97,6 +97,8 @@ static int can_esp32_twai_init(const struct device *dev)
|
|||
|
||||
const struct can_driver_api can_esp32_twai_driver_api = {
|
||||
.get_capabilities = can_sja1000_get_capabilities,
|
||||
.start = can_sja1000_start,
|
||||
.stop = can_sja1000_stop,
|
||||
.set_mode = can_sja1000_set_mode,
|
||||
.set_timing = can_sja1000_set_timing,
|
||||
.send = can_sja1000_send,
|
||||
|
|
|
@ -147,6 +147,22 @@ static inline int z_vrfy_can_get_capabilities(const struct device *dev, can_mode
|
|||
}
|
||||
#include <syscalls/can_get_capabilities_mrsh.c>
|
||||
|
||||
static inline int z_vrfy_can_start(const struct device *dev)
|
||||
{
|
||||
Z_OOPS(Z_SYSCALL_DRIVER_CAN(dev, start));
|
||||
|
||||
return z_impl_can_start(dev);
|
||||
}
|
||||
#include <syscalls/can_start_mrsh.c>
|
||||
|
||||
static inline int z_vrfy_can_stop(const struct device *dev)
|
||||
{
|
||||
Z_OOPS(Z_SYSCALL_DRIVER_CAN(dev, stop));
|
||||
|
||||
return z_impl_can_stop(dev);
|
||||
}
|
||||
#include <syscalls/can_stop_mrsh.c>
|
||||
|
||||
static inline int z_vrfy_can_set_mode(const struct device *dev, can_mode_t mode)
|
||||
{
|
||||
Z_OOPS(Z_SYSCALL_DRIVER_CAN(dev, set_mode));
|
||||
|
|
|
@ -38,6 +38,7 @@ struct can_loopback_data {
|
|||
struct k_msgq tx_msgq;
|
||||
char msgq_buffer[CONFIG_CAN_LOOPBACK_TX_MSGQ_SIZE * sizeof(struct can_loopback_frame)];
|
||||
struct k_thread tx_thread_data;
|
||||
bool started;
|
||||
|
||||
K_KERNEL_STACK_MEMBER(tx_thread_stack,
|
||||
CONFIG_CAN_LOOPBACK_TX_THREAD_STACK_SIZE);
|
||||
|
@ -118,6 +119,10 @@ static int can_loopback_send(const struct device *dev,
|
|||
return -EINVAL;
|
||||
}
|
||||
|
||||
if (!data->started) {
|
||||
return -ENETDOWN;
|
||||
}
|
||||
|
||||
if (!data->loopback) {
|
||||
return 0;
|
||||
}
|
||||
|
@ -212,10 +217,40 @@ static int can_loopback_get_capabilities(const struct device *dev, can_mode_t *c
|
|||
return 0;
|
||||
}
|
||||
|
||||
static int can_loopback_start(const struct device *dev)
|
||||
{
|
||||
struct can_loopback_data *data = dev->data;
|
||||
|
||||
if (data->started) {
|
||||
return -EALREADY;
|
||||
}
|
||||
|
||||
data->started = true;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int can_loopback_stop(const struct device *dev)
|
||||
{
|
||||
struct can_loopback_data *data = dev->data;
|
||||
|
||||
if (!data->started) {
|
||||
return -EALREADY;
|
||||
}
|
||||
|
||||
data->started = false;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int can_loopback_set_mode(const struct device *dev, can_mode_t mode)
|
||||
{
|
||||
struct can_loopback_data *data = dev->data;
|
||||
|
||||
if (data->started) {
|
||||
return -EBUSY;
|
||||
}
|
||||
|
||||
#ifdef CONFIG_CAN_FD_MODE
|
||||
if ((mode & ~(CAN_MODE_LOOPBACK | CAN_MODE_FD)) != 0) {
|
||||
LOG_ERR("unsupported mode: 0x%08x", mode);
|
||||
|
@ -235,9 +270,14 @@ static int can_loopback_set_mode(const struct device *dev, can_mode_t mode)
|
|||
static int can_loopback_set_timing(const struct device *dev,
|
||||
const struct can_timing *timing)
|
||||
{
|
||||
ARG_UNUSED(dev);
|
||||
struct can_loopback_data *data = dev->data;
|
||||
|
||||
ARG_UNUSED(timing);
|
||||
|
||||
if (data->started) {
|
||||
return -EBUSY;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
@ -245,9 +285,14 @@ static int can_loopback_set_timing(const struct device *dev,
|
|||
static int can_loopback_set_timing_data(const struct device *dev,
|
||||
const struct can_timing *timing)
|
||||
{
|
||||
ARG_UNUSED(dev);
|
||||
struct can_loopback_data *data = dev->data;
|
||||
|
||||
ARG_UNUSED(timing);
|
||||
|
||||
if (data->started) {
|
||||
return -EBUSY;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
#endif /* CONFIG_CAN_FD_MODE */
|
||||
|
@ -255,10 +300,14 @@ static int can_loopback_set_timing_data(const struct device *dev,
|
|||
static int can_loopback_get_state(const struct device *dev, enum can_state *state,
|
||||
struct can_bus_err_cnt *err_cnt)
|
||||
{
|
||||
ARG_UNUSED(dev);
|
||||
struct can_loopback_data *data = dev->data;
|
||||
|
||||
if (state != NULL) {
|
||||
*state = CAN_STATE_ERROR_ACTIVE;
|
||||
if (data->started) {
|
||||
*state = CAN_STATE_ERROR_ACTIVE;
|
||||
} else {
|
||||
*state = CAN_STATE_STOPPED;
|
||||
}
|
||||
}
|
||||
|
||||
if (err_cnt) {
|
||||
|
@ -272,9 +321,14 @@ static int can_loopback_get_state(const struct device *dev, enum can_state *stat
|
|||
#ifndef CONFIG_CAN_AUTO_BUS_OFF_RECOVERY
|
||||
static int can_loopback_recover(const struct device *dev, k_timeout_t timeout)
|
||||
{
|
||||
ARG_UNUSED(dev);
|
||||
struct can_loopback_data *data = dev->data;
|
||||
|
||||
ARG_UNUSED(timeout);
|
||||
|
||||
if (!data->started) {
|
||||
return -ENETDOWN;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
#endif /* CONFIG_CAN_AUTO_BUS_OFF_RECOVERY */
|
||||
|
@ -304,6 +358,8 @@ static int can_loopback_get_max_filters(const struct device *dev, enum can_ide i
|
|||
|
||||
static const struct can_driver_api can_loopback_driver_api = {
|
||||
.get_capabilities = can_loopback_get_capabilities,
|
||||
.start = can_loopback_start,
|
||||
.stop = can_loopback_stop,
|
||||
.set_mode = can_loopback_set_mode,
|
||||
.set_timing = can_loopback_set_timing,
|
||||
.send = can_loopback_send,
|
||||
|
|
|
@ -73,7 +73,7 @@ static int can_exit_sleep_mode(struct can_mcan_reg *can)
|
|||
return 0;
|
||||
}
|
||||
|
||||
static int can_enter_init_mode(struct can_mcan_reg *can, k_timeout_t timeout)
|
||||
static int can_enter_init_mode(struct can_mcan_reg *can, k_timeout_t timeout)
|
||||
{
|
||||
int64_t start_time;
|
||||
|
||||
|
@ -90,7 +90,7 @@ static int can_enter_init_mode(struct can_mcan_reg *can, k_timeout_t timeout)
|
|||
return 0;
|
||||
}
|
||||
|
||||
static int can_leave_init_mode(struct can_mcan_reg *can, k_timeout_t timeout)
|
||||
static int can_leave_init_mode(struct can_mcan_reg *can, k_timeout_t timeout)
|
||||
{
|
||||
int64_t start_time;
|
||||
|
||||
|
@ -173,26 +173,15 @@ int can_mcan_set_timing(const struct device *dev,
|
|||
const struct can_timing *timing)
|
||||
{
|
||||
const struct can_mcan_config *cfg = dev->config;
|
||||
struct can_mcan_data *data = dev->data;
|
||||
struct can_mcan_reg *can = cfg->can;
|
||||
int ret;
|
||||
|
||||
ret = can_enter_init_mode(can, K_MSEC(CAN_INIT_TIMEOUT));
|
||||
if (ret) {
|
||||
LOG_ERR("Failed to enter init mode");
|
||||
return -EIO;
|
||||
if (data->started) {
|
||||
return -EBUSY;
|
||||
}
|
||||
|
||||
/* Configuration Change Enable */
|
||||
can->cccr |= CAN_MCAN_CCCR_CCE;
|
||||
|
||||
can_mcan_configure_timing(can, timing, NULL);
|
||||
|
||||
ret = can_leave_init_mode(can, K_MSEC(CAN_INIT_TIMEOUT));
|
||||
if (ret) {
|
||||
LOG_ERR("Failed to leave init mode");
|
||||
return -EIO;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
@ -201,26 +190,15 @@ int can_mcan_set_timing_data(const struct device *dev,
|
|||
const struct can_timing *timing_data)
|
||||
{
|
||||
const struct can_mcan_config *cfg = dev->config;
|
||||
struct can_mcan_data *data = dev->data;
|
||||
struct can_mcan_reg *can = cfg->can;
|
||||
int ret;
|
||||
|
||||
ret = can_enter_init_mode(can, K_MSEC(CAN_INIT_TIMEOUT));
|
||||
if (ret) {
|
||||
LOG_ERR("Failed to enter init mode");
|
||||
return -EIO;
|
||||
if (data->started) {
|
||||
return -EBUSY;
|
||||
}
|
||||
|
||||
/* Configuration Change Enable */
|
||||
can->cccr |= CAN_MCAN_CCCR_CCE;
|
||||
|
||||
can_mcan_configure_timing(can, NULL, timing_data);
|
||||
|
||||
ret = can_leave_init_mode(can, K_MSEC(CAN_INIT_TIMEOUT));
|
||||
if (ret) {
|
||||
LOG_ERR("Failed to leave init mode");
|
||||
return -EIO;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
#endif /* CONFIG_CAN_FD_MODE */
|
||||
|
@ -238,11 +216,79 @@ int can_mcan_get_capabilities(const struct device *dev, can_mode_t *cap)
|
|||
return 0;
|
||||
}
|
||||
|
||||
int can_mcan_start(const struct device *dev)
|
||||
{
|
||||
const struct can_mcan_config *cfg = dev->config;
|
||||
struct can_mcan_data *data = dev->data;
|
||||
struct can_mcan_reg *can = cfg->can;
|
||||
int ret;
|
||||
|
||||
if (data->started) {
|
||||
return -EALREADY;
|
||||
}
|
||||
|
||||
if (cfg->phy != NULL) {
|
||||
ret = can_transceiver_enable(cfg->phy);
|
||||
if (ret != 0) {
|
||||
LOG_ERR("failed to enable CAN transceiver (err %d)", ret);
|
||||
return ret;
|
||||
}
|
||||
}
|
||||
|
||||
ret = can_leave_init_mode(can, K_MSEC(CAN_INIT_TIMEOUT));
|
||||
if (ret) {
|
||||
LOG_ERR("failed to leave init mode");
|
||||
|
||||
if (cfg->phy != NULL) {
|
||||
/* Attempt to disable the CAN transceiver in case of error */
|
||||
(void)can_transceiver_disable(cfg->phy);
|
||||
}
|
||||
|
||||
return -EIO;
|
||||
}
|
||||
|
||||
data->started = true;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int can_mcan_stop(const struct device *dev)
|
||||
{
|
||||
const struct can_mcan_config *cfg = dev->config;
|
||||
struct can_mcan_data *data = dev->data;
|
||||
struct can_mcan_reg *can = cfg->can;
|
||||
int ret;
|
||||
|
||||
if (!data->started) {
|
||||
return -EALREADY;
|
||||
}
|
||||
|
||||
ret = can_enter_init_mode(can, K_MSEC(CAN_INIT_TIMEOUT));
|
||||
if (ret != 0) {
|
||||
LOG_ERR("Failed to enter init mode");
|
||||
return -EIO;
|
||||
}
|
||||
|
||||
if (cfg->phy != NULL) {
|
||||
ret = can_transceiver_disable(cfg->phy);
|
||||
if (ret != 0) {
|
||||
LOG_ERR("failed to disable CAN transceiver (err %d)", ret);
|
||||
return ret;
|
||||
}
|
||||
}
|
||||
|
||||
can_mcan_enable_configuration_change(dev);
|
||||
|
||||
data->started = false;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int can_mcan_set_mode(const struct device *dev, can_mode_t mode)
|
||||
{
|
||||
const struct can_mcan_config *cfg = dev->config;
|
||||
struct can_mcan_data *data = dev->data;
|
||||
struct can_mcan_reg *can = cfg->can;
|
||||
int ret;
|
||||
|
||||
#ifdef CONFIG_CAN_FD_MODE
|
||||
if ((mode & ~(CAN_MODE_LOOPBACK | CAN_MODE_LISTENONLY | CAN_MODE_FD)) != 0) {
|
||||
|
@ -256,29 +302,10 @@ int can_mcan_set_mode(const struct device *dev, can_mode_t mode)
|
|||
}
|
||||
#endif /* CONFIG_CAN_FD_MODE */
|
||||
|
||||
if (cfg->phy != NULL) {
|
||||
ret = can_transceiver_enable(cfg->phy);
|
||||
if (ret != 0) {
|
||||
LOG_ERR("failed to enable CAN transceiver (err %d)", ret);
|
||||
return ret;
|
||||
}
|
||||
if (data->started) {
|
||||
return -EBUSY;
|
||||
}
|
||||
|
||||
ret = can_enter_init_mode(can, K_MSEC(CAN_INIT_TIMEOUT));
|
||||
if (ret) {
|
||||
LOG_ERR("Failed to enter init mode");
|
||||
|
||||
if (cfg->phy != NULL) {
|
||||
/* Attempt to disable the CAN transceiver in case of error */
|
||||
(void)can_transceiver_disable(cfg->phy);
|
||||
}
|
||||
|
||||
return -EIO;
|
||||
}
|
||||
|
||||
/* Configuration Change Enable */
|
||||
can->cccr |= CAN_MCAN_CCCR_CCE;
|
||||
|
||||
if ((mode & CAN_MODE_LOOPBACK) != 0) {
|
||||
/* Loopback mode */
|
||||
can->cccr |= CAN_MCAN_CCCR_TEST;
|
||||
|
@ -302,16 +329,6 @@ int can_mcan_set_mode(const struct device *dev, can_mode_t mode)
|
|||
}
|
||||
#endif /* CONFIG_CAN_FD_MODE */
|
||||
|
||||
ret = can_leave_init_mode(can, K_MSEC(CAN_INIT_TIMEOUT));
|
||||
if (ret) {
|
||||
LOG_ERR("Failed to leave init mode");
|
||||
|
||||
if (cfg->phy != NULL) {
|
||||
/* Attempt to disable the CAN transceiver in case of error */
|
||||
(void)can_transceiver_disable(cfg->phy);
|
||||
}
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
@ -351,19 +368,16 @@ int can_mcan_init(const struct device *dev)
|
|||
ret = can_exit_sleep_mode(can);
|
||||
if (ret) {
|
||||
LOG_ERR("Failed to exit sleep mode");
|
||||
ret = -EIO;
|
||||
goto done;
|
||||
return -EIO;
|
||||
}
|
||||
|
||||
ret = can_enter_init_mode(can, K_MSEC(CAN_INIT_TIMEOUT));
|
||||
if (ret) {
|
||||
LOG_ERR("Failed to enter init mode");
|
||||
ret = -EIO;
|
||||
goto done;
|
||||
return -EIO;
|
||||
}
|
||||
|
||||
/* Configuration Change Enable */
|
||||
can->cccr |= CAN_MCAN_CCCR_CCE;
|
||||
can_mcan_enable_configuration_change(dev);
|
||||
|
||||
LOG_DBG("IP rel: %lu.%lu.%lu %02lu.%lu.%lu",
|
||||
(can->crel & CAN_MCAN_CREL_REL) >> CAN_MCAN_CREL_REL_POS,
|
||||
|
@ -446,8 +460,7 @@ int can_mcan_init(const struct device *dev)
|
|||
cfg->sample_point);
|
||||
if (ret == -EINVAL) {
|
||||
LOG_ERR("Can't find timing for given param");
|
||||
ret = -EIO;
|
||||
goto done;
|
||||
return -EIO;
|
||||
}
|
||||
LOG_DBG("Presc: %d, TS1: %d, TS2: %d",
|
||||
timing.prescaler, timing.phase_seg1, timing.phase_seg2);
|
||||
|
@ -468,8 +481,7 @@ int can_mcan_init(const struct device *dev)
|
|||
cfg->sample_point_data);
|
||||
if (ret == -EINVAL) {
|
||||
LOG_ERR("Can't find timing for given dataphase param");
|
||||
ret = -EIO;
|
||||
goto done;
|
||||
return -EIO;
|
||||
}
|
||||
|
||||
LOG_DBG("Sample-point err data phase: %d", ret);
|
||||
|
@ -510,20 +522,7 @@ int can_mcan_init(const struct device *dev)
|
|||
memset32_volatile(msg_ram, 0, sizeof(struct can_mcan_msg_sram));
|
||||
sys_cache_data_range(msg_ram, sizeof(struct can_mcan_msg_sram), K_CACHE_WB);
|
||||
|
||||
ret = can_leave_init_mode(can, K_MSEC(CAN_INIT_TIMEOUT));
|
||||
if (ret) {
|
||||
LOG_ERR("Failed to leave init mode");
|
||||
ret = -EIO;
|
||||
goto done;
|
||||
}
|
||||
|
||||
done:
|
||||
if (ret != 0 && cfg->phy != NULL) {
|
||||
/* Attempt to disable the CAN transceiver in case of error */
|
||||
(void)can_transceiver_disable(cfg->phy);
|
||||
}
|
||||
|
||||
return ret;
|
||||
return 0;
|
||||
}
|
||||
|
||||
static void can_mcan_state_change_handler(const struct device *dev)
|
||||
|
@ -744,10 +743,13 @@ int can_mcan_get_state(const struct device *dev, enum can_state *state,
|
|||
struct can_bus_err_cnt *err_cnt)
|
||||
{
|
||||
const struct can_mcan_config *cfg = dev->config;
|
||||
struct can_mcan_data *data = dev->data;
|
||||
struct can_mcan_reg *can = cfg->can;
|
||||
|
||||
if (state != NULL) {
|
||||
if (can->psr & CAN_MCAN_PSR_BO) {
|
||||
if (!data->started) {
|
||||
*state = CAN_STATE_STOPPED;
|
||||
} else if (can->psr & CAN_MCAN_PSR_BO) {
|
||||
*state = CAN_STATE_BUS_OFF;
|
||||
} else if (can->psr & CAN_MCAN_PSR_EP) {
|
||||
*state = CAN_STATE_ERROR_PASSIVE;
|
||||
|
@ -773,8 +775,13 @@ int can_mcan_get_state(const struct device *dev, enum can_state *state,
|
|||
int can_mcan_recover(const struct device *dev, k_timeout_t timeout)
|
||||
{
|
||||
const struct can_mcan_config *cfg = dev->config;
|
||||
struct can_mcan_data *data = dev->data;
|
||||
struct can_mcan_reg *can = cfg->can;
|
||||
|
||||
if (!data->started) {
|
||||
return -ENETDOWN;
|
||||
}
|
||||
|
||||
return can_leave_init_mode(can, timeout);
|
||||
}
|
||||
#endif /* CONFIG_CAN_AUTO_BUS_OFF_RECOVERY */
|
||||
|
@ -824,6 +831,10 @@ int can_mcan_send(const struct device *dev,
|
|||
return -EINVAL;
|
||||
}
|
||||
|
||||
if (!data->started) {
|
||||
return -ENETDOWN;
|
||||
}
|
||||
|
||||
if (can->psr & CAN_MCAN_PSR_BO) {
|
||||
return -ENETUNREACH;
|
||||
}
|
||||
|
|
|
@ -184,6 +184,7 @@ struct can_mcan_data {
|
|||
uint8_t ext_filt_rtr;
|
||||
uint8_t ext_filt_rtr_mask;
|
||||
struct can_mcan_mm mm;
|
||||
bool started;
|
||||
void *custom;
|
||||
} __aligned(4);
|
||||
|
||||
|
@ -259,6 +260,10 @@ struct can_mcan_reg;
|
|||
|
||||
int can_mcan_get_capabilities(const struct device *dev, can_mode_t *cap);
|
||||
|
||||
int can_mcan_start(const struct device *dev);
|
||||
|
||||
int can_mcan_stop(const struct device *dev);
|
||||
|
||||
int can_mcan_set_mode(const struct device *dev, can_mode_t mode);
|
||||
|
||||
int can_mcan_set_timing(const struct device *dev,
|
||||
|
|
|
@ -287,24 +287,6 @@ const int mcp2515_set_mode_int(const struct device *dev, uint8_t mcp2515_mode)
|
|||
return 0;
|
||||
}
|
||||
|
||||
static int mcp2515_get_mode(const struct device *dev, uint8_t *mode)
|
||||
{
|
||||
uint8_t canstat;
|
||||
|
||||
if (mode == NULL) {
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
if (mcp2515_cmd_read_reg(dev, MCP2515_ADDR_CANSTAT, &canstat, 1)) {
|
||||
return -EIO;
|
||||
}
|
||||
|
||||
*mode = (canstat & MCP2515_CANSTAT_MODE_MASK)
|
||||
>> MCP2515_CANSTAT_MODE_POS;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int mcp2515_get_core_clock(const struct device *dev, uint32_t *rate)
|
||||
{
|
||||
const struct mcp2515_config *dev_cfg = dev->config;
|
||||
|
@ -339,9 +321,12 @@ static int mcp2515_set_timing(const struct device *dev,
|
|||
return -EINVAL;
|
||||
}
|
||||
|
||||
if (dev_data->started) {
|
||||
return -EBUSY;
|
||||
}
|
||||
|
||||
/* CNF3, CNF2, CNF1, CANINTE */
|
||||
uint8_t config_buf[4];
|
||||
uint8_t mode;
|
||||
|
||||
/* CNF1; SJW<7:6> | BRP<5:0> */
|
||||
__ASSERT(timing->prescaler > 0, "Prescaler should be bigger than zero");
|
||||
|
@ -395,18 +380,6 @@ static int mcp2515_set_timing(const struct device *dev,
|
|||
|
||||
k_mutex_lock(&dev_data->mutex, K_FOREVER);
|
||||
|
||||
ret = mcp2515_get_mode(dev, &mode);
|
||||
if (ret < 0) {
|
||||
LOG_ERR("Failed to read device mode [%d]", ret);
|
||||
goto done;
|
||||
}
|
||||
|
||||
ret = mcp2515_set_mode_int(dev, MCP2515_MODE_CONFIGURATION);
|
||||
if (ret < 0) {
|
||||
LOG_ERR("Failed to enter configuration mode [%d]", ret);
|
||||
goto done;
|
||||
}
|
||||
|
||||
ret = mcp2515_cmd_write_reg(dev, MCP2515_ADDR_CNF3, config_buf,
|
||||
sizeof(config_buf));
|
||||
if (ret < 0) {
|
||||
|
@ -428,13 +401,6 @@ static int mcp2515_set_timing(const struct device *dev,
|
|||
goto done;
|
||||
}
|
||||
|
||||
/* Restore previous mode */
|
||||
ret = mcp2515_set_mode_int(dev, mode);
|
||||
if (ret < 0) {
|
||||
LOG_ERR("Failed to restore mode [%d]", ret);
|
||||
goto done;
|
||||
}
|
||||
|
||||
done:
|
||||
k_mutex_unlock(&dev_data->mutex);
|
||||
return ret;
|
||||
|
@ -449,41 +415,27 @@ static int mcp2515_get_capabilities(const struct device *dev, can_mode_t *cap)
|
|||
return 0;
|
||||
}
|
||||
|
||||
static int mcp2515_set_mode(const struct device *dev, can_mode_t mode)
|
||||
static int mcp2515_start(const struct device *dev)
|
||||
{
|
||||
const struct mcp2515_config *dev_cfg = dev->config;
|
||||
struct mcp2515_data *dev_data = dev->data;
|
||||
uint8_t mcp2515_mode;
|
||||
int ret;
|
||||
|
||||
switch (mode) {
|
||||
case CAN_MODE_NORMAL:
|
||||
mcp2515_mode = MCP2515_MODE_NORMAL;
|
||||
break;
|
||||
case CAN_MODE_LISTENONLY:
|
||||
mcp2515_mode = MCP2515_MODE_SILENT;
|
||||
break;
|
||||
case CAN_MODE_LOOPBACK:
|
||||
mcp2515_mode = MCP2515_MODE_LOOPBACK;
|
||||
break;
|
||||
default:
|
||||
LOG_ERR("Unsupported CAN Mode %u", mode);
|
||||
return -ENOTSUP;
|
||||
if (dev_data->started) {
|
||||
return -EALREADY;
|
||||
}
|
||||
|
||||
k_mutex_lock(&dev_data->mutex, K_FOREVER);
|
||||
|
||||
if (dev_cfg->phy != NULL) {
|
||||
ret = can_transceiver_enable(dev_cfg->phy);
|
||||
if (ret != 0) {
|
||||
LOG_ERR("failed to enable CAN transceiver (err %d)", ret);
|
||||
goto done;
|
||||
LOG_ERR("Failed to enable CAN transceiver [%d]", ret);
|
||||
return ret;
|
||||
}
|
||||
}
|
||||
|
||||
k_usleep(MCP2515_OSC_STARTUP_US);
|
||||
k_mutex_lock(&dev_data->mutex, K_FOREVER);
|
||||
|
||||
ret = mcp2515_set_mode_int(dev, mcp2515_mode);
|
||||
ret = mcp2515_set_mode_int(dev, dev_data->mcp2515_mode);
|
||||
if (ret < 0) {
|
||||
LOG_ERR("Failed to set the mode [%d]", ret);
|
||||
|
||||
|
@ -491,13 +443,75 @@ static int mcp2515_set_mode(const struct device *dev, can_mode_t mode)
|
|||
/* Attempt to disable the CAN transceiver in case of error */
|
||||
(void)can_transceiver_disable(dev_cfg->phy);
|
||||
}
|
||||
} else {
|
||||
dev_data->started = true;
|
||||
}
|
||||
|
||||
done:
|
||||
k_mutex_unlock(&dev_data->mutex);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
static int mcp2515_stop(const struct device *dev)
|
||||
{
|
||||
const struct mcp2515_config *dev_cfg = dev->config;
|
||||
struct mcp2515_data *dev_data = dev->data;
|
||||
int ret;
|
||||
|
||||
if (!dev_data->started) {
|
||||
return -EALREADY;
|
||||
}
|
||||
|
||||
k_mutex_lock(&dev_data->mutex, K_FOREVER);
|
||||
|
||||
ret = mcp2515_set_mode_int(dev, MCP2515_MODE_CONFIGURATION);
|
||||
if (ret < 0) {
|
||||
LOG_ERR("Failed to enter configuration mode [%d]", ret);
|
||||
k_mutex_unlock(&dev_data->mutex);
|
||||
return ret;
|
||||
}
|
||||
|
||||
dev_data->started = false;
|
||||
|
||||
k_mutex_unlock(&dev_data->mutex);
|
||||
|
||||
if (dev_cfg->phy != NULL) {
|
||||
ret = can_transceiver_disable(dev_cfg->phy);
|
||||
if (ret != 0) {
|
||||
LOG_ERR("Failed to disable CAN transceiver [%d]", ret);
|
||||
return ret;
|
||||
}
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int mcp2515_set_mode(const struct device *dev, can_mode_t mode)
|
||||
{
|
||||
struct mcp2515_data *dev_data = dev->data;
|
||||
|
||||
if (dev_data->started) {
|
||||
return -EBUSY;
|
||||
}
|
||||
|
||||
switch (mode) {
|
||||
case CAN_MODE_NORMAL:
|
||||
dev_data->mcp2515_mode = MCP2515_MODE_NORMAL;
|
||||
break;
|
||||
case CAN_MODE_LISTENONLY:
|
||||
dev_data->mcp2515_mode = MCP2515_MODE_SILENT;
|
||||
break;
|
||||
case CAN_MODE_LOOPBACK:
|
||||
dev_data->mcp2515_mode = MCP2515_MODE_LOOPBACK;
|
||||
break;
|
||||
default:
|
||||
LOG_ERR("Unsupported CAN Mode %u", mode);
|
||||
return -ENOTSUP;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int mcp2515_send(const struct device *dev,
|
||||
const struct can_frame *frame,
|
||||
k_timeout_t timeout, can_tx_callback_t callback,
|
||||
|
@ -516,6 +530,10 @@ static int mcp2515_send(const struct device *dev,
|
|||
return -EINVAL;
|
||||
}
|
||||
|
||||
if (!dev_data->started) {
|
||||
return -ENETDOWN;
|
||||
}
|
||||
|
||||
if (k_sem_take(&dev_data->tx_sem, timeout) != 0) {
|
||||
return -EAGAIN;
|
||||
}
|
||||
|
@ -681,6 +699,7 @@ static void mcp2515_tx_done(const struct device *dev, uint8_t tx_idx)
|
|||
static int mcp2515_get_state(const struct device *dev, enum can_state *state,
|
||||
struct can_bus_err_cnt *err_cnt)
|
||||
{
|
||||
struct mcp2515_data *dev_data = dev->data;
|
||||
uint8_t eflg;
|
||||
uint8_t err_cnt_buf[2];
|
||||
int ret;
|
||||
|
@ -692,7 +711,9 @@ static int mcp2515_get_state(const struct device *dev, enum can_state *state,
|
|||
}
|
||||
|
||||
if (state != NULL) {
|
||||
if (eflg & MCP2515_EFLG_TXBO) {
|
||||
if (!dev_data->started) {
|
||||
*state = CAN_STATE_STOPPED;
|
||||
} else if (eflg & MCP2515_EFLG_TXBO) {
|
||||
*state = CAN_STATE_BUS_OFF;
|
||||
} else if ((eflg & MCP2515_EFLG_RXEP) || (eflg & MCP2515_EFLG_TXEP)) {
|
||||
*state = CAN_STATE_ERROR_PASSIVE;
|
||||
|
@ -742,9 +763,14 @@ static void mcp2515_handle_errors(const struct device *dev)
|
|||
#ifndef CONFIG_CAN_AUTO_BUS_OFF_RECOVERY
|
||||
static int mcp2515_recover(const struct device *dev, k_timeout_t timeout)
|
||||
{
|
||||
ARG_UNUSED(dev);
|
||||
struct mcp2515_data *dev_data = dev->data;
|
||||
|
||||
ARG_UNUSED(timeout);
|
||||
|
||||
if (!dev_data->started) {
|
||||
return -ENETDOWN;
|
||||
}
|
||||
|
||||
return -ENOTSUP;
|
||||
}
|
||||
#endif
|
||||
|
@ -838,6 +864,8 @@ static void mcp2515_int_gpio_callback(const struct device *dev,
|
|||
static const struct can_driver_api can_api_funcs = {
|
||||
.get_capabilities = mcp2515_get_capabilities,
|
||||
.set_timing = mcp2515_set_timing,
|
||||
.start = mcp2515_start,
|
||||
.stop = mcp2515_stop,
|
||||
.set_mode = mcp2515_set_mode,
|
||||
.send = mcp2515_send,
|
||||
.add_rx_filter = mcp2515_add_rx_filter,
|
||||
|
@ -957,6 +985,8 @@ static int mcp2515_init(const struct device *dev)
|
|||
}
|
||||
}
|
||||
|
||||
k_usleep(MCP2515_OSC_STARTUP_US);
|
||||
|
||||
ret = can_set_timing(dev, &timing);
|
||||
if (ret) {
|
||||
return ret;
|
||||
|
|
|
@ -45,6 +45,8 @@ struct mcp2515_data {
|
|||
/* general data */
|
||||
struct k_mutex mutex;
|
||||
enum can_state old_state;
|
||||
uint8_t mcp2515_mode;
|
||||
bool started;
|
||||
uint8_t sjw;
|
||||
};
|
||||
|
||||
|
|
|
@ -126,6 +126,7 @@ struct mcux_flexcan_data {
|
|||
can_state_change_callback_t state_change_cb;
|
||||
void *state_change_cb_data;
|
||||
struct can_timing timing;
|
||||
bool started;
|
||||
};
|
||||
|
||||
static int mcux_flexcan_get_core_clock(const struct device *dev, uint32_t *rate)
|
||||
|
@ -155,27 +156,21 @@ static int mcux_flexcan_set_timing(const struct device *dev,
|
|||
const struct can_timing *timing)
|
||||
{
|
||||
struct mcux_flexcan_data *data = dev->data;
|
||||
const struct mcux_flexcan_config *config = dev->config;
|
||||
uint8_t sjw_backup = data->timing.sjw;
|
||||
flexcan_timing_config_t timing_tmp;
|
||||
|
||||
if (!timing) {
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
if (data->started) {
|
||||
return -EBUSY;
|
||||
}
|
||||
|
||||
data->timing = *timing;
|
||||
if (timing->sjw == CAN_SJW_NO_CHANGE) {
|
||||
data->timing.sjw = sjw_backup;
|
||||
}
|
||||
|
||||
timing_tmp.preDivider = data->timing.prescaler - 1U;
|
||||
timing_tmp.rJumpwidth = data->timing.sjw - 1U;
|
||||
timing_tmp.phaseSeg1 = data->timing.phase_seg1 - 1U;
|
||||
timing_tmp.phaseSeg2 = data->timing.phase_seg2 - 1U;
|
||||
timing_tmp.propSeg = data->timing.prop_seg - 1U;
|
||||
|
||||
FLEXCAN_SetTimingConfig(config->base, &timing_tmp);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
@ -188,16 +183,15 @@ static int mcux_flexcan_get_capabilities(const struct device *dev, can_mode_t *c
|
|||
return 0;
|
||||
}
|
||||
|
||||
static int mcux_flexcan_set_mode(const struct device *dev, can_mode_t mode)
|
||||
static int mcux_flexcan_start(const struct device *dev)
|
||||
{
|
||||
const struct mcux_flexcan_config *config = dev->config;
|
||||
uint32_t ctrl1;
|
||||
uint32_t mcr;
|
||||
struct mcux_flexcan_data *data = dev->data;
|
||||
flexcan_timing_config_t timing;
|
||||
int err;
|
||||
|
||||
if ((mode & ~(CAN_MODE_LOOPBACK | CAN_MODE_LISTENONLY | CAN_MODE_3_SAMPLES)) != 0) {
|
||||
LOG_ERR("unsupported mode: 0x%08x", mode);
|
||||
return -ENOTSUP;
|
||||
if (data->started) {
|
||||
return -EALREADY;
|
||||
}
|
||||
|
||||
if (config->phy != NULL) {
|
||||
|
@ -208,8 +202,63 @@ static int mcux_flexcan_set_mode(const struct device *dev, can_mode_t mode)
|
|||
}
|
||||
}
|
||||
|
||||
/* Clear error counters */
|
||||
config->base->ECR &= ~(CAN_ECR_TXERRCNT_MASK | CAN_ECR_RXERRCNT_MASK);
|
||||
|
||||
/* Delay this until start since setting the timing automatically exits freeze mode */
|
||||
timing.preDivider = data->timing.prescaler - 1U;
|
||||
timing.rJumpwidth = data->timing.sjw - 1U;
|
||||
timing.phaseSeg1 = data->timing.phase_seg1 - 1U;
|
||||
timing.phaseSeg2 = data->timing.phase_seg2 - 1U;
|
||||
timing.propSeg = data->timing.prop_seg - 1U;
|
||||
FLEXCAN_SetTimingConfig(config->base, &timing);
|
||||
|
||||
data->started = true;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int mcux_flexcan_stop(const struct device *dev)
|
||||
{
|
||||
const struct mcux_flexcan_config *config = dev->config;
|
||||
struct mcux_flexcan_data *data = dev->data;
|
||||
int err;
|
||||
|
||||
if (!data->started) {
|
||||
return -EALREADY;
|
||||
}
|
||||
|
||||
FLEXCAN_EnterFreezeMode(config->base);
|
||||
|
||||
if (config->phy != NULL) {
|
||||
err = can_transceiver_disable(config->phy);
|
||||
if (err != 0) {
|
||||
LOG_ERR("failed to disable CAN transceiver (err %d)", err);
|
||||
return err;
|
||||
}
|
||||
}
|
||||
|
||||
data->started = false;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int mcux_flexcan_set_mode(const struct device *dev, can_mode_t mode)
|
||||
{
|
||||
const struct mcux_flexcan_config *config = dev->config;
|
||||
struct mcux_flexcan_data *data = dev->data;
|
||||
uint32_t ctrl1;
|
||||
uint32_t mcr;
|
||||
|
||||
if (data->started) {
|
||||
return -EBUSY;
|
||||
}
|
||||
|
||||
if ((mode & ~(CAN_MODE_LOOPBACK | CAN_MODE_LISTENONLY | CAN_MODE_3_SAMPLES)) != 0) {
|
||||
LOG_ERR("unsupported mode: 0x%08x", mode);
|
||||
return -ENOTSUP;
|
||||
}
|
||||
|
||||
ctrl1 = config->base->CTRL1;
|
||||
mcr = config->base->MCR;
|
||||
|
||||
|
@ -242,8 +291,6 @@ static int mcux_flexcan_set_mode(const struct device *dev, can_mode_t mode)
|
|||
config->base->CTRL1 = ctrl1;
|
||||
config->base->MCR = mcr;
|
||||
|
||||
FLEXCAN_ExitFreezeMode(config->base);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
@ -319,20 +366,25 @@ static int mcux_flexcan_get_state(const struct device *dev, enum can_state *stat
|
|||
struct can_bus_err_cnt *err_cnt)
|
||||
{
|
||||
const struct mcux_flexcan_config *config = dev->config;
|
||||
struct mcux_flexcan_data *data = dev->data;
|
||||
uint64_t status_flags;
|
||||
|
||||
if (state != NULL) {
|
||||
status_flags = FLEXCAN_GetStatusFlags(config->base);
|
||||
|
||||
if ((status_flags & CAN_ESR1_FLTCONF(2)) != 0U) {
|
||||
*state = CAN_STATE_BUS_OFF;
|
||||
} else if ((status_flags & CAN_ESR1_FLTCONF(1)) != 0U) {
|
||||
*state = CAN_STATE_ERROR_PASSIVE;
|
||||
} else if ((status_flags &
|
||||
(kFLEXCAN_TxErrorWarningFlag | kFLEXCAN_RxErrorWarningFlag)) != 0) {
|
||||
*state = CAN_STATE_ERROR_WARNING;
|
||||
if (!data->started) {
|
||||
*state = CAN_STATE_STOPPED;
|
||||
} else {
|
||||
*state = CAN_STATE_ERROR_ACTIVE;
|
||||
status_flags = FLEXCAN_GetStatusFlags(config->base);
|
||||
|
||||
if ((status_flags & CAN_ESR1_FLTCONF(2)) != 0U) {
|
||||
*state = CAN_STATE_BUS_OFF;
|
||||
} else if ((status_flags & CAN_ESR1_FLTCONF(1)) != 0U) {
|
||||
*state = CAN_STATE_ERROR_PASSIVE;
|
||||
} else if ((status_flags &
|
||||
(kFLEXCAN_TxErrorWarningFlag | kFLEXCAN_RxErrorWarningFlag)) != 0) {
|
||||
*state = CAN_STATE_ERROR_WARNING;
|
||||
} else {
|
||||
*state = CAN_STATE_ERROR_ACTIVE;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -361,6 +413,10 @@ static int mcux_flexcan_send(const struct device *dev,
|
|||
return -EINVAL;
|
||||
}
|
||||
|
||||
if (!data->started) {
|
||||
return -ENETDOWN;
|
||||
}
|
||||
|
||||
(void)mcux_flexcan_get_state(dev, &state, NULL);
|
||||
if (state == CAN_STATE_BUS_OFF) {
|
||||
LOG_DBG("Transmit failed, bus-off");
|
||||
|
@ -432,8 +488,13 @@ static int mcux_flexcan_add_rx_filter(const struct device *dev,
|
|||
data->rx_cbs[alloc].arg = user_data;
|
||||
data->rx_cbs[alloc].function = callback;
|
||||
|
||||
FLEXCAN_SetRxIndividualMask(config->base, ALLOC_IDX_TO_RXMB_IDX(alloc),
|
||||
mask);
|
||||
/* The indidual RX mask registers can only be written in freeze mode */
|
||||
FLEXCAN_EnterFreezeMode(config->base);
|
||||
config->base->RXIMR[ALLOC_IDX_TO_RXMB_IDX(alloc)] = mask;
|
||||
if (data->started) {
|
||||
FLEXCAN_ExitFreezeMode(config->base);
|
||||
}
|
||||
|
||||
FLEXCAN_SetRxMbConfig(config->base, ALLOC_IDX_TO_RXMB_IDX(alloc),
|
||||
&data->rx_cbs[alloc].mb_config, true);
|
||||
|
||||
|
@ -466,10 +527,15 @@ static void mcux_flexcan_set_state_change_callback(const struct device *dev,
|
|||
static int mcux_flexcan_recover(const struct device *dev, k_timeout_t timeout)
|
||||
{
|
||||
const struct mcux_flexcan_config *config = dev->config;
|
||||
struct mcux_flexcan_data *data = dev->data;
|
||||
enum can_state state;
|
||||
uint64_t start_time;
|
||||
int ret = 0;
|
||||
|
||||
if (!data->started) {
|
||||
return -ENETDOWN;
|
||||
}
|
||||
|
||||
(void)mcux_flexcan_get_state(dev, &state, NULL);
|
||||
if (state != CAN_STATE_BUS_OFF) {
|
||||
return 0;
|
||||
|
@ -775,17 +841,23 @@ static int mcux_flexcan_init(const struct device *dev)
|
|||
flexcan_config.enableIndividMask = true;
|
||||
flexcan_config.enableLoopBack = false;
|
||||
flexcan_config.disableSelfReception = true;
|
||||
flexcan_config.enableListenOnlyMode = false;
|
||||
flexcan_config.enableListenOnlyMode = true;
|
||||
|
||||
flexcan_config.timingConfig.rJumpwidth = data->timing.sjw - 1U;
|
||||
flexcan_config.timingConfig.propSeg = data->timing.prop_seg - 1U;
|
||||
flexcan_config.timingConfig.phaseSeg1 = data->timing.phase_seg1 - 1U;
|
||||
flexcan_config.timingConfig.phaseSeg2 = data->timing.phase_seg2 - 1U;
|
||||
|
||||
/* Initialize in listen-only mode since FLEXCAN_Init() exits freeze mode */
|
||||
FLEXCAN_Init(config->base, &flexcan_config, clock_freq);
|
||||
FLEXCAN_TransferCreateHandle(config->base, &data->handle,
|
||||
mcux_flexcan_transfer_callback, data);
|
||||
|
||||
/* Manually enter freeze mode, set normal mode, and clear error counters */
|
||||
FLEXCAN_EnterFreezeMode(config->base);
|
||||
(void)mcux_flexcan_set_mode(dev, CAN_MODE_NORMAL);
|
||||
config->base->ECR &= ~(CAN_ECR_TXERRCNT_MASK | CAN_ECR_RXERRCNT_MASK);
|
||||
|
||||
config->irq_config_func(dev);
|
||||
|
||||
#ifndef CONFIG_CAN_AUTO_BUS_OFF_RECOVERY
|
||||
|
@ -799,6 +871,8 @@ static int mcux_flexcan_init(const struct device *dev)
|
|||
|
||||
static const struct can_driver_api mcux_flexcan_driver_api = {
|
||||
.get_capabilities = mcux_flexcan_get_capabilities,
|
||||
.start = mcux_flexcan_start,
|
||||
.stop = mcux_flexcan_stop,
|
||||
.set_mode = mcux_flexcan_set_mode,
|
||||
.set_timing = mcux_flexcan_set_timing,
|
||||
.send = mcux_flexcan_send,
|
||||
|
|
|
@ -77,6 +77,8 @@ static int mcux_mcan_init(const struct device *dev)
|
|||
|
||||
static const struct can_driver_api mcux_mcan_driver_api = {
|
||||
.get_capabilities = can_mcan_get_capabilities,
|
||||
.start = can_mcan_start,
|
||||
.stop = can_mcan_stop,
|
||||
.set_mode = can_mcan_set_mode,
|
||||
.set_timing = can_mcan_set_timing,
|
||||
.send = can_mcan_send,
|
||||
|
|
|
@ -39,6 +39,7 @@ struct can_npl_data {
|
|||
bool mode_fd;
|
||||
int dev_fd; /* Linux socket file descriptor */
|
||||
struct k_thread rx_thread;
|
||||
bool started;
|
||||
|
||||
K_KERNEL_STACK_MEMBER(rx_thread_stack, CONFIG_ARCH_POSIX_RECOMMENDED_STACK_SIZE);
|
||||
};
|
||||
|
@ -102,7 +103,7 @@ static void rx_thread(void *arg1, void *arg2, void *arg3)
|
|||
|
||||
k_sem_give(&data->tx_idle);
|
||||
|
||||
if (!data->loopback) {
|
||||
if (!data->loopback || !data->started) {
|
||||
continue;
|
||||
}
|
||||
}
|
||||
|
@ -158,6 +159,10 @@ static int can_npl_send(const struct device *dev, const struct can_frame *frame,
|
|||
return -EIO;
|
||||
}
|
||||
|
||||
if (!data->started) {
|
||||
return -ENETDOWN;
|
||||
}
|
||||
|
||||
socketcan_from_can_frame(frame, &sframe);
|
||||
|
||||
if (k_sem_take(&data->tx_idle, timeout) != 0) {
|
||||
|
@ -250,6 +255,32 @@ static int can_npl_get_capabilities(const struct device *dev, can_mode_t *cap)
|
|||
return 0;
|
||||
}
|
||||
|
||||
static int can_npl_start(const struct device *dev)
|
||||
{
|
||||
struct can_npl_data *data = dev->data;
|
||||
|
||||
if (data->started) {
|
||||
return -EALREADY;
|
||||
}
|
||||
|
||||
data->started = true;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int can_npl_stop(const struct device *dev)
|
||||
{
|
||||
struct can_npl_data *data = dev->data;
|
||||
|
||||
if (!data->started) {
|
||||
return -EALREADY;
|
||||
}
|
||||
|
||||
data->started = false;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int can_npl_set_mode(const struct device *dev, can_mode_t mode)
|
||||
{
|
||||
struct can_npl_data *data = dev->data;
|
||||
|
@ -266,6 +297,10 @@ static int can_npl_set_mode(const struct device *dev, can_mode_t mode)
|
|||
}
|
||||
#endif /* CONFIG_CAN_FD_MODE */
|
||||
|
||||
if (data->started) {
|
||||
return -EBUSY;
|
||||
}
|
||||
|
||||
/* loopback is handled internally in rx_thread */
|
||||
data->loopback = (mode & CAN_MODE_LOOPBACK) != 0;
|
||||
|
||||
|
@ -277,18 +312,28 @@ static int can_npl_set_mode(const struct device *dev, can_mode_t mode)
|
|||
|
||||
static int can_npl_set_timing(const struct device *dev, const struct can_timing *timing)
|
||||
{
|
||||
ARG_UNUSED(dev);
|
||||
struct can_npl_data *data = dev->data;
|
||||
|
||||
ARG_UNUSED(timing);
|
||||
|
||||
if (data->started) {
|
||||
return -EBUSY;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
#ifdef CONFIG_CAN_FD_MODE
|
||||
static int can_npl_set_timing_data(const struct device *dev, const struct can_timing *timing)
|
||||
{
|
||||
ARG_UNUSED(dev);
|
||||
struct can_npl_data *data = dev->data;
|
||||
|
||||
ARG_UNUSED(timing);
|
||||
|
||||
if (data->started) {
|
||||
return -EBUSY;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
#endif /* CONFIG_CAN_FD_MODE */
|
||||
|
@ -296,11 +341,15 @@ static int can_npl_set_timing_data(const struct device *dev, const struct can_ti
|
|||
static int can_npl_get_state(const struct device *dev, enum can_state *state,
|
||||
struct can_bus_err_cnt *err_cnt)
|
||||
{
|
||||
ARG_UNUSED(dev);
|
||||
struct can_npl_data *data = dev->data;
|
||||
|
||||
if (state != NULL) {
|
||||
/* SocketCAN does not forward error frames by default */
|
||||
*state = CAN_STATE_ERROR_ACTIVE;
|
||||
if (!data->started) {
|
||||
*state = CAN_STATE_STOPPED;
|
||||
} else {
|
||||
/* SocketCAN does not forward error frames by default */
|
||||
*state = CAN_STATE_ERROR_ACTIVE;
|
||||
}
|
||||
}
|
||||
|
||||
if (err_cnt) {
|
||||
|
@ -314,9 +363,14 @@ static int can_npl_get_state(const struct device *dev, enum can_state *state,
|
|||
#ifndef CONFIG_CAN_AUTO_BUS_OFF_RECOVERY
|
||||
static int can_npl_recover(const struct device *dev, k_timeout_t timeout)
|
||||
{
|
||||
ARG_UNUSED(dev);
|
||||
struct can_npl_data *data = dev->data;
|
||||
|
||||
ARG_UNUSED(timeout);
|
||||
|
||||
if (!data->started) {
|
||||
return -ENETDOWN;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
#endif /* CONFIG_CAN_AUTO_BUS_OFF_RECOVERY */
|
||||
|
@ -346,6 +400,8 @@ static int can_npl_get_max_filters(const struct device *dev, enum can_ide id_typ
|
|||
}
|
||||
|
||||
static const struct can_driver_api can_npl_driver_api = {
|
||||
.start = can_npl_start,
|
||||
.stop = can_npl_stop,
|
||||
.get_capabilities = can_npl_get_capabilities,
|
||||
.set_mode = can_npl_set_mode,
|
||||
.set_timing = can_npl_set_timing,
|
||||
|
|
|
@ -204,6 +204,7 @@ struct can_rcar_data {
|
|||
can_state_change_callback_t state_change_cb;
|
||||
void *state_change_cb_data;
|
||||
enum can_state state;
|
||||
bool started;
|
||||
};
|
||||
|
||||
static inline uint16_t can_rcar_read16(const struct can_rcar_cfg *config,
|
||||
|
@ -580,6 +581,77 @@ static int can_rcar_get_capabilities(const struct device *dev, can_mode_t *cap)
|
|||
return 0;
|
||||
}
|
||||
|
||||
static int can_rcar_start(const struct device *dev)
|
||||
{
|
||||
const struct can_rcar_cfg *config = dev->config;
|
||||
struct can_rcar_data *data = dev->data;
|
||||
int ret;
|
||||
|
||||
if (data->started) {
|
||||
return -EALREADY;
|
||||
}
|
||||
|
||||
if (config->phy != NULL) {
|
||||
ret = can_transceiver_enable(config->phy);
|
||||
if (ret != 0) {
|
||||
LOG_ERR("failed to enable CAN transceiver (err %d)", ret);
|
||||
return ret;
|
||||
}
|
||||
}
|
||||
|
||||
k_mutex_lock(&data->inst_mutex, K_FOREVER);
|
||||
|
||||
ret = can_rcar_enter_operation_mode(config);
|
||||
if (ret != 0) {
|
||||
LOG_ERR("failed to enter operation mode (err %d)", ret);
|
||||
|
||||
if (config->phy != NULL) {
|
||||
/* Attempt to disable the CAN transceiver in case of error */
|
||||
(void)can_transceiver_disable(config->phy);
|
||||
}
|
||||
} else {
|
||||
data->started = true;
|
||||
}
|
||||
|
||||
k_mutex_unlock(&data->inst_mutex);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
static int can_rcar_stop(const struct device *dev)
|
||||
{
|
||||
const struct can_rcar_cfg *config = dev->config;
|
||||
struct can_rcar_data *data = dev->data;
|
||||
int ret;
|
||||
|
||||
if (!data->started) {
|
||||
return -EALREADY;
|
||||
}
|
||||
|
||||
k_mutex_lock(&data->inst_mutex, K_FOREVER);
|
||||
|
||||
ret = can_rcar_enter_halt_mode(config);
|
||||
if (ret != 0) {
|
||||
LOG_ERR("failed to enter halt mode (err %d)", ret);
|
||||
k_mutex_unlock(&data->inst_mutex);
|
||||
return ret;
|
||||
}
|
||||
|
||||
data->started = false;
|
||||
|
||||
k_mutex_unlock(&data->inst_mutex);
|
||||
|
||||
if (config->phy != NULL) {
|
||||
ret = can_transceiver_disable(config->phy);
|
||||
if (ret != 0) {
|
||||
LOG_ERR("failed to disable CAN transceiver (err %d)", ret);
|
||||
return ret;
|
||||
}
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int can_rcar_set_mode(const struct device *dev, can_mode_t mode)
|
||||
{
|
||||
const struct can_rcar_cfg *config = dev->config;
|
||||
|
@ -592,6 +664,10 @@ static int can_rcar_set_mode(const struct device *dev, can_mode_t mode)
|
|||
return -ENOTSUP;
|
||||
}
|
||||
|
||||
if (data->started) {
|
||||
return -EBUSY;
|
||||
}
|
||||
|
||||
k_mutex_lock(&data->inst_mutex, K_FOREVER);
|
||||
|
||||
if ((mode & (CAN_MODE_LOOPBACK | CAN_MODE_LISTENONLY)) ==
|
||||
|
@ -610,34 +686,11 @@ static int can_rcar_set_mode(const struct device *dev, can_mode_t mode)
|
|||
tcr = 0;
|
||||
}
|
||||
|
||||
/* Enable CAN transceiver */
|
||||
if (config->phy != NULL) {
|
||||
ret = can_transceiver_enable(config->phy);
|
||||
if (ret != 0) {
|
||||
LOG_ERR("failed to enable CAN transceiver (err %d)", ret);
|
||||
goto unlock;
|
||||
}
|
||||
}
|
||||
|
||||
/* Writing to TCR registers must be done in halt mode */
|
||||
ret = can_rcar_enter_halt_mode(config);
|
||||
if (ret) {
|
||||
goto unlock;
|
||||
}
|
||||
|
||||
sys_write8(tcr, config->reg_addr + RCAR_CAN_TCR);
|
||||
/* Go back to operation mode */
|
||||
ret = can_rcar_enter_operation_mode(config);
|
||||
|
||||
unlock:
|
||||
if (ret != 0) {
|
||||
if (config->phy != NULL) {
|
||||
/* Attempt to disable the CAN transceiver in case of error */
|
||||
(void)can_transceiver_disable(config->phy);
|
||||
}
|
||||
}
|
||||
|
||||
k_mutex_unlock(&data->inst_mutex);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
@ -680,6 +733,10 @@ static int can_rcar_set_timing(const struct device *dev,
|
|||
struct reg_backup regs[3] = { { RCAR_CAN_TCR, 0 }, { RCAR_CAN_TFCR, 0 }
|
||||
, { RCAR_CAN_RFCR, 0 } };
|
||||
|
||||
if (data->started) {
|
||||
return -EBUSY;
|
||||
}
|
||||
|
||||
k_mutex_lock(&data->inst_mutex, K_FOREVER);
|
||||
|
||||
/* Changing bittiming should be done in reset mode.
|
||||
|
@ -711,9 +768,6 @@ static int can_rcar_set_timing(const struct device *dev,
|
|||
sys_write8(regs[i].value, config->reg_addr + regs[i].address);
|
||||
}
|
||||
|
||||
/* Go back to operation mode */
|
||||
ret = can_rcar_enter_operation_mode(config);
|
||||
|
||||
unlock:
|
||||
k_mutex_unlock(&data->inst_mutex);
|
||||
return ret;
|
||||
|
@ -736,7 +790,11 @@ static int can_rcar_get_state(const struct device *dev, enum can_state *state,
|
|||
struct can_rcar_data *data = dev->data;
|
||||
|
||||
if (state != NULL) {
|
||||
*state = data->state;
|
||||
if (!data->started) {
|
||||
*state = CAN_STATE_STOPPED;
|
||||
} else {
|
||||
*state = data->state;
|
||||
}
|
||||
}
|
||||
|
||||
if (err_cnt != NULL) {
|
||||
|
@ -754,6 +812,10 @@ static int can_rcar_recover(const struct device *dev, k_timeout_t timeout)
|
|||
int64_t start_time;
|
||||
int ret;
|
||||
|
||||
if (!data->started) {
|
||||
return -ENETDOWN;
|
||||
}
|
||||
|
||||
if (data->state != CAN_STATE_BUS_OFF) {
|
||||
return 0;
|
||||
}
|
||||
|
@ -810,6 +872,10 @@ static int can_rcar_send(const struct device *dev, const struct can_frame *frame
|
|||
return -EINVAL;
|
||||
}
|
||||
|
||||
if (!data->started) {
|
||||
return -ENETDOWN;
|
||||
}
|
||||
|
||||
/* Wait for a slot into the tx FIFO */
|
||||
if (k_sem_take(&data->tx_sem, timeout) != 0) {
|
||||
return -EAGAIN;
|
||||
|
@ -1050,14 +1116,8 @@ static int can_rcar_init(const struct device *dev)
|
|||
/* Enable interrupts for all type of errors */
|
||||
sys_write8(0xFF, config->reg_addr + RCAR_CAN_EIER);
|
||||
|
||||
/* Go to operation mode */
|
||||
ret = can_rcar_enter_operation_mode(config);
|
||||
__ASSERT(!ret, "Fail to set CAN controller to operation mode");
|
||||
if (ret) {
|
||||
return ret;
|
||||
}
|
||||
|
||||
config->init_func(dev);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
@ -1087,6 +1147,8 @@ static int can_rcar_get_max_bitrate(const struct device *dev, uint32_t *max_bitr
|
|||
|
||||
static const struct can_driver_api can_rcar_driver_api = {
|
||||
.get_capabilities = can_rcar_get_capabilities,
|
||||
.start = can_rcar_start,
|
||||
.stop = can_rcar_stop,
|
||||
.set_mode = can_rcar_set_mode,
|
||||
.set_timing = can_rcar_set_timing,
|
||||
.send = can_rcar_send,
|
||||
|
|
|
@ -71,6 +71,8 @@ static int can_sam_init(const struct device *dev)
|
|||
|
||||
static const struct can_driver_api can_sam_driver_api = {
|
||||
.get_capabilities = can_mcan_get_capabilities,
|
||||
.start = can_mcan_start,
|
||||
.stop = can_mcan_stop,
|
||||
.set_mode = can_mcan_set_mode,
|
||||
.set_timing = can_mcan_set_timing,
|
||||
.send = can_mcan_send,
|
||||
|
|
|
@ -193,6 +193,8 @@ static const char *can_shell_state_to_string(enum can_state state)
|
|||
return "error-passive";
|
||||
case CAN_STATE_BUS_OFF:
|
||||
return "bus-off";
|
||||
case CAN_STATE_STOPPED:
|
||||
return "stopped";
|
||||
default:
|
||||
return "unknown";
|
||||
}
|
||||
|
|
|
@ -79,13 +79,22 @@ static inline int can_sja1000_leave_reset_mode(const struct device *dev)
|
|||
return 0;
|
||||
}
|
||||
|
||||
static inline void can_sja1000_clear_errors(const struct device *dev)
|
||||
{
|
||||
/* Clear error counters */
|
||||
can_sja1000_write_reg(dev, CAN_SJA1000_RXERR, 0);
|
||||
can_sja1000_write_reg(dev, CAN_SJA1000_TXERR, 0);
|
||||
|
||||
/* Clear error capture */
|
||||
(void)can_sja1000_read_reg(dev, CAN_SJA1000_ECC);
|
||||
}
|
||||
|
||||
int can_sja1000_set_timing(const struct device *dev, const struct can_timing *timing)
|
||||
{
|
||||
struct can_sja1000_data *data = dev->data;
|
||||
uint8_t btr0;
|
||||
uint8_t btr1;
|
||||
uint8_t sjw;
|
||||
int err;
|
||||
|
||||
__ASSERT_NO_MSG(timing->sjw == CAN_SJW_NO_CHANGE || (timing->sjw >= 1 && timing->sjw <= 4));
|
||||
__ASSERT_NO_MSG(timing->prop_seg == 0);
|
||||
|
@ -93,13 +102,12 @@ int can_sja1000_set_timing(const struct device *dev, const struct can_timing *ti
|
|||
__ASSERT_NO_MSG(timing->phase_seg2 >= 1 && timing->phase_seg2 <= 8);
|
||||
__ASSERT_NO_MSG(timing->prescaler >= 1 && timing->prescaler <= 64);
|
||||
|
||||
k_mutex_lock(&data->mod_lock, K_FOREVER);
|
||||
|
||||
err = can_sja1000_enter_reset_mode(dev);
|
||||
if (err != 0) {
|
||||
goto unlock;
|
||||
if (data->started) {
|
||||
return -EBUSY;
|
||||
}
|
||||
|
||||
k_mutex_lock(&data->mod_lock, K_FOREVER);
|
||||
|
||||
if (timing->sjw == CAN_SJW_NO_CHANGE) {
|
||||
sjw = data->sjw;
|
||||
} else {
|
||||
|
@ -119,15 +127,9 @@ int can_sja1000_set_timing(const struct device *dev, const struct can_timing *ti
|
|||
can_sja1000_write_reg(dev, CAN_SJA1000_BTR0, btr0);
|
||||
can_sja1000_write_reg(dev, CAN_SJA1000_BTR1, btr1);
|
||||
|
||||
err = can_sja1000_leave_reset_mode(dev);
|
||||
if (err != 0) {
|
||||
goto unlock;
|
||||
}
|
||||
|
||||
unlock:
|
||||
k_mutex_unlock(&data->mod_lock);
|
||||
|
||||
return err;
|
||||
return 0;
|
||||
}
|
||||
|
||||
int can_sja1000_get_capabilities(const struct device *dev, can_mode_t *cap)
|
||||
|
@ -140,18 +142,14 @@ int can_sja1000_get_capabilities(const struct device *dev, can_mode_t *cap)
|
|||
return 0;
|
||||
}
|
||||
|
||||
int can_sja1000_set_mode(const struct device *dev, can_mode_t mode)
|
||||
int can_sja1000_start(const struct device *dev)
|
||||
{
|
||||
const struct can_sja1000_config *config = dev->config;
|
||||
struct can_sja1000_data *data = dev->data;
|
||||
uint8_t btr1;
|
||||
uint8_t mod;
|
||||
int err;
|
||||
|
||||
if ((mode & ~(CAN_MODE_LOOPBACK | CAN_MODE_LISTENONLY | CAN_MODE_ONE_SHOT |
|
||||
CAN_MODE_3_SAMPLES)) != 0) {
|
||||
LOG_ERR("unsupported mode: 0x%08x", mode);
|
||||
return -ENOTSUP;
|
||||
if (data->started) {
|
||||
return -EALREADY;
|
||||
}
|
||||
|
||||
if (config->phy != NULL) {
|
||||
|
@ -162,13 +160,70 @@ int can_sja1000_set_mode(const struct device *dev, can_mode_t mode)
|
|||
}
|
||||
}
|
||||
|
||||
k_mutex_lock(&data->mod_lock, K_FOREVER);
|
||||
can_sja1000_clear_errors(dev);
|
||||
|
||||
err = can_sja1000_leave_reset_mode(dev);
|
||||
if (err != 0) {
|
||||
if (config->phy != NULL) {
|
||||
/* Attempt to disable the CAN transceiver in case of error */
|
||||
(void)can_transceiver_disable(config->phy);
|
||||
}
|
||||
|
||||
return err;
|
||||
}
|
||||
|
||||
data->started = true;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int can_sja1000_stop(const struct device *dev)
|
||||
{
|
||||
const struct can_sja1000_config *config = dev->config;
|
||||
struct can_sja1000_data *data = dev->data;
|
||||
int err;
|
||||
|
||||
if (!data->started) {
|
||||
return -EALREADY;
|
||||
}
|
||||
|
||||
err = can_sja1000_enter_reset_mode(dev);
|
||||
if (err != 0) {
|
||||
goto unlock;
|
||||
return err;
|
||||
}
|
||||
|
||||
if (config->phy != NULL) {
|
||||
err = can_transceiver_disable(config->phy);
|
||||
if (err != 0) {
|
||||
LOG_ERR("failed to disable CAN transceiver (err %d)", err);
|
||||
return err;
|
||||
}
|
||||
}
|
||||
|
||||
data->started = false;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int can_sja1000_set_mode(const struct device *dev, can_mode_t mode)
|
||||
{
|
||||
const struct can_sja1000_config *config = dev->config;
|
||||
struct can_sja1000_data *data = dev->data;
|
||||
uint8_t btr1;
|
||||
uint8_t mod;
|
||||
|
||||
if ((mode & ~(CAN_MODE_LOOPBACK | CAN_MODE_LISTENONLY | CAN_MODE_ONE_SHOT |
|
||||
CAN_MODE_3_SAMPLES)) != 0) {
|
||||
LOG_ERR("unsupported mode: 0x%08x", mode);
|
||||
return -ENOTSUP;
|
||||
}
|
||||
|
||||
if (data->started) {
|
||||
return -EBUSY;
|
||||
}
|
||||
|
||||
k_mutex_lock(&data->mod_lock, K_FOREVER);
|
||||
|
||||
mod = can_sja1000_read_reg(dev, CAN_SJA1000_MOD);
|
||||
mod |= CAN_SJA1000_MOD_AFM;
|
||||
|
||||
|
@ -195,16 +250,11 @@ int can_sja1000_set_mode(const struct device *dev, can_mode_t mode)
|
|||
can_sja1000_write_reg(dev, CAN_SJA1000_MOD, mod);
|
||||
can_sja1000_write_reg(dev, CAN_SJA1000_BTR1, btr1);
|
||||
|
||||
err = can_sja1000_leave_reset_mode(dev);
|
||||
if (err != 0) {
|
||||
goto unlock;
|
||||
}
|
||||
|
||||
data->mode = mode;
|
||||
unlock:
|
||||
|
||||
k_mutex_unlock(&data->mod_lock);
|
||||
|
||||
return err;
|
||||
return 0;
|
||||
}
|
||||
|
||||
static void can_sja1000_read_frame(const struct device *dev, struct can_frame *frame)
|
||||
|
@ -311,6 +361,10 @@ int can_sja1000_send(const struct device *dev, const struct can_frame *frame, k_
|
|||
return -EINVAL;
|
||||
}
|
||||
|
||||
if (!data->started) {
|
||||
return -ENETDOWN;
|
||||
}
|
||||
|
||||
if (data->state == CAN_STATE_BUS_OFF) {
|
||||
LOG_DBG("transmit failed, bus-off");
|
||||
return -ENETUNREACH;
|
||||
|
@ -398,6 +452,10 @@ int can_sja1000_recover(const struct device *dev, k_timeout_t timeout)
|
|||
uint8_t sr;
|
||||
int err;
|
||||
|
||||
if (!data->started) {
|
||||
return -ENETDOWN;
|
||||
}
|
||||
|
||||
sr = can_sja1000_read_reg(dev, CAN_SJA1000_SR);
|
||||
if ((sr & CAN_SJA1000_SR_BS) == 0) {
|
||||
return 0;
|
||||
|
@ -439,7 +497,11 @@ int can_sja1000_get_state(const struct device *dev, enum can_state *state,
|
|||
struct can_sja1000_data *data = dev->data;
|
||||
|
||||
if (state != NULL) {
|
||||
*state = data->state;
|
||||
if (!data->started) {
|
||||
*state = CAN_STATE_STOPPED;
|
||||
} else {
|
||||
*state = data->state;
|
||||
}
|
||||
}
|
||||
|
||||
if (err_cnt != NULL) {
|
||||
|
@ -546,11 +608,8 @@ static void can_sja1000_handle_error_warning_irq(const struct device *dev)
|
|||
data->state = CAN_STATE_BUS_OFF;
|
||||
can_sja1000_tx_done(dev, -ENETUNREACH);
|
||||
#ifdef CONFIG_CAN_AUTO_BUS_OFF_RECOVERY
|
||||
/* Recover bus now unless interrupted in the middle of a MOD register change. */
|
||||
err = k_mutex_lock(&data->mod_lock, K_NO_WAIT);
|
||||
if (err == 0) {
|
||||
if (data->started) {
|
||||
(void)can_sja1000_leave_reset_mode(dev);
|
||||
k_mutex_unlock(&data->mod_lock);
|
||||
}
|
||||
#endif /* CONFIG_CAN_AUTO_BUS_OFF_RECOVERY */
|
||||
} else if ((sr & CAN_SJA1000_SR_ES) != 0) {
|
||||
|
@ -683,17 +742,13 @@ int can_sja1000_init(const struct device *dev)
|
|||
/* Set output control */
|
||||
can_sja1000_write_reg(dev, CAN_SJA1000_OCR, config->ocr);
|
||||
|
||||
/* Clear error counters */
|
||||
can_sja1000_write_reg(dev, CAN_SJA1000_RXERR, 0);
|
||||
can_sja1000_write_reg(dev, CAN_SJA1000_TXERR, 0);
|
||||
|
||||
/* Clear error capture */
|
||||
(void)can_sja1000_read_reg(dev, CAN_SJA1000_ECC);
|
||||
/* Clear error counters and error capture */
|
||||
can_sja1000_clear_errors(dev);
|
||||
|
||||
/* Set error warning limit */
|
||||
can_sja1000_write_reg(dev, CAN_SJA1000_EWLR, 96);
|
||||
|
||||
/* Enter normal mode */
|
||||
/* Set normal mode */
|
||||
data->mode = CAN_MODE_NORMAL;
|
||||
err = can_sja1000_set_mode(dev, CAN_MODE_NORMAL);
|
||||
if (err != 0) {
|
||||
|
|
|
@ -100,6 +100,7 @@ struct can_sja1000_data {
|
|||
ATOMIC_DEFINE(rx_allocs, CONFIG_CAN_MAX_FILTER);
|
||||
struct can_sja1000_rx_filter filters[CONFIG_CAN_MAX_FILTER];
|
||||
struct k_mutex mod_lock;
|
||||
bool started;
|
||||
can_mode_t mode;
|
||||
enum can_state state;
|
||||
can_state_change_callback_t state_change_cb;
|
||||
|
@ -122,6 +123,10 @@ int can_sja1000_set_timing(const struct device *dev, const struct can_timing *ti
|
|||
|
||||
int can_sja1000_get_capabilities(const struct device *dev, can_mode_t *cap);
|
||||
|
||||
int can_sja1000_start(const struct device *dev);
|
||||
|
||||
int can_sja1000_stop(const struct device *dev);
|
||||
|
||||
int can_sja1000_set_mode(const struct device *dev, can_mode_t mode);
|
||||
|
||||
int can_sja1000_send(const struct device *dev, const struct can_frame *frame, k_timeout_t timeout,
|
||||
|
|
|
@ -127,10 +127,13 @@ static int can_stm32_get_state(const struct device *dev, enum can_state *state,
|
|||
struct can_bus_err_cnt *err_cnt)
|
||||
{
|
||||
const struct can_stm32_config *cfg = dev->config;
|
||||
struct can_stm32_data *data = dev->data;
|
||||
CAN_TypeDef *can = cfg->can;
|
||||
|
||||
if (state != NULL) {
|
||||
if (can->ESR & CAN_ESR_BOFF) {
|
||||
if (!data->started) {
|
||||
*state = CAN_STATE_STOPPED;
|
||||
} else if (can->ESR & CAN_ESR_BOFF) {
|
||||
*state = CAN_STATE_BUS_OFF;
|
||||
} else if (can->ESR & CAN_ESR_EPVF) {
|
||||
*state = CAN_STATE_ERROR_PASSIVE;
|
||||
|
@ -352,12 +355,91 @@ static int can_stm32_get_capabilities(const struct device *dev, can_mode_t *cap)
|
|||
return 0;
|
||||
}
|
||||
|
||||
static int can_stm32_start(const struct device *dev)
|
||||
{
|
||||
const struct can_stm32_config *cfg = dev->config;
|
||||
struct can_stm32_data *data = dev->data;
|
||||
CAN_TypeDef *can = cfg->can;
|
||||
int ret = 0;
|
||||
|
||||
k_mutex_lock(&data->inst_mutex, K_FOREVER);
|
||||
|
||||
if (data->started) {
|
||||
ret = -EALREADY;
|
||||
goto unlock;
|
||||
}
|
||||
|
||||
if (cfg->phy != NULL) {
|
||||
ret = can_transceiver_enable(cfg->phy);
|
||||
if (ret != 0) {
|
||||
LOG_ERR("failed to enable CAN transceiver (err %d)", ret);
|
||||
goto unlock;
|
||||
}
|
||||
}
|
||||
|
||||
ret = can_stm32_leave_init_mode(can);
|
||||
if (ret < 0) {
|
||||
LOG_ERR("Failed to leave init mode");
|
||||
|
||||
if (cfg->phy != NULL) {
|
||||
/* Attempt to disable the CAN transceiver in case of error */
|
||||
(void)can_transceiver_disable(cfg->phy);
|
||||
}
|
||||
|
||||
ret = -EIO;
|
||||
goto unlock;
|
||||
}
|
||||
|
||||
data->started = true;
|
||||
|
||||
unlock:
|
||||
k_mutex_unlock(&data->inst_mutex);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
static int can_stm32_stop(const struct device *dev)
|
||||
{
|
||||
const struct can_stm32_config *cfg = dev->config;
|
||||
struct can_stm32_data *data = dev->data;
|
||||
CAN_TypeDef *can = cfg->can;
|
||||
int ret = 0;
|
||||
|
||||
k_mutex_lock(&data->inst_mutex, K_FOREVER);
|
||||
|
||||
if (!data->started) {
|
||||
ret = -EALREADY;
|
||||
goto unlock;
|
||||
}
|
||||
|
||||
ret = can_stm32_enter_init_mode(can);
|
||||
if (ret < 0) {
|
||||
LOG_ERR("Failed to enter init mode");
|
||||
ret = -EIO;
|
||||
goto unlock;
|
||||
}
|
||||
|
||||
if (cfg->phy != NULL) {
|
||||
ret = can_transceiver_disable(cfg->phy);
|
||||
if (ret != 0) {
|
||||
LOG_ERR("failed to enable CAN transceiver (err %d)", ret);
|
||||
goto unlock;
|
||||
}
|
||||
}
|
||||
|
||||
data->started = false;
|
||||
|
||||
unlock:
|
||||
k_mutex_unlock(&data->inst_mutex);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
static int can_stm32_set_mode(const struct device *dev, can_mode_t mode)
|
||||
{
|
||||
const struct can_stm32_config *cfg = dev->config;
|
||||
CAN_TypeDef *can = cfg->can;
|
||||
struct can_stm32_data *data = dev->data;
|
||||
int ret;
|
||||
|
||||
LOG_DBG("Set mode %d", mode);
|
||||
|
||||
|
@ -366,22 +448,12 @@ static int can_stm32_set_mode(const struct device *dev, can_mode_t mode)
|
|||
return -ENOTSUP;
|
||||
}
|
||||
|
||||
if (data->started) {
|
||||
return -EBUSY;
|
||||
}
|
||||
|
||||
k_mutex_lock(&data->inst_mutex, K_FOREVER);
|
||||
|
||||
if (cfg->phy != NULL) {
|
||||
ret = can_transceiver_enable(cfg->phy);
|
||||
if (ret != 0) {
|
||||
LOG_ERR("failed to enable CAN transceiver (err %d)", ret);
|
||||
goto done;
|
||||
}
|
||||
}
|
||||
|
||||
ret = can_stm32_enter_init_mode(can);
|
||||
if (ret) {
|
||||
LOG_ERR("Failed to enter init mode");
|
||||
goto done;
|
||||
}
|
||||
|
||||
if ((mode & CAN_MODE_LOOPBACK) != 0) {
|
||||
/* Loopback mode */
|
||||
can->BTR |= CAN_BTR_LBKM;
|
||||
|
@ -403,20 +475,9 @@ static int can_stm32_set_mode(const struct device *dev, can_mode_t mode)
|
|||
can->MCR &= ~CAN_MCR_NART;
|
||||
}
|
||||
|
||||
done:
|
||||
ret = can_stm32_leave_init_mode(can);
|
||||
if (ret) {
|
||||
LOG_ERR("Failed to leave init mode");
|
||||
|
||||
if (cfg->phy != NULL) {
|
||||
/* Attempt to disable the CAN transceiver in case of error */
|
||||
(void)can_transceiver_disable(cfg->phy);
|
||||
}
|
||||
}
|
||||
|
||||
k_mutex_unlock(&data->inst_mutex);
|
||||
|
||||
return ret;
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int can_stm32_set_timing(const struct device *dev,
|
||||
|
@ -425,13 +486,12 @@ static int can_stm32_set_timing(const struct device *dev,
|
|||
const struct can_stm32_config *cfg = dev->config;
|
||||
CAN_TypeDef *can = cfg->can;
|
||||
struct can_stm32_data *data = dev->data;
|
||||
int ret = -EIO;
|
||||
|
||||
k_mutex_lock(&data->inst_mutex, K_FOREVER);
|
||||
ret = can_stm32_enter_init_mode(can);
|
||||
if (ret) {
|
||||
LOG_ERR("Failed to enter init mode");
|
||||
goto done;
|
||||
|
||||
if (data->started) {
|
||||
k_mutex_unlock(&data->inst_mutex);
|
||||
return -EBUSY;
|
||||
}
|
||||
|
||||
can->BTR = (can->BTR & ~(CAN_BTR_BRP_Msk | CAN_BTR_TS1_Msk | CAN_BTR_TS2_Msk)) |
|
||||
|
@ -444,16 +504,9 @@ static int can_stm32_set_timing(const struct device *dev,
|
|||
(((timing->sjw - 1) << CAN_BTR_SJW_Pos) & CAN_BTR_SJW_Msk);
|
||||
}
|
||||
|
||||
ret = can_stm32_leave_init_mode(can);
|
||||
if (ret) {
|
||||
LOG_ERR("Failed to leave init mode");
|
||||
} else {
|
||||
ret = 0;
|
||||
}
|
||||
|
||||
done:
|
||||
k_mutex_unlock(&data->inst_mutex);
|
||||
return ret;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int can_stm32_get_core_clock(const struct device *dev, uint32_t *rate)
|
||||
|
@ -630,6 +683,10 @@ static int can_stm32_recover(const struct device *dev, k_timeout_t timeout)
|
|||
int ret = -EAGAIN;
|
||||
int64_t start_time;
|
||||
|
||||
if (!data->started) {
|
||||
return -ENETDOWN;
|
||||
}
|
||||
|
||||
if (!(can->ESR & CAN_ESR_BOFF)) {
|
||||
return 0;
|
||||
}
|
||||
|
@ -691,6 +748,10 @@ static int can_stm32_send(const struct device *dev, const struct can_frame *fram
|
|||
return -EINVAL;
|
||||
}
|
||||
|
||||
if (!data->started) {
|
||||
return -ENETDOWN;
|
||||
}
|
||||
|
||||
if (can->ESR & CAN_ESR_BOFF) {
|
||||
return -ENETUNREACH;
|
||||
}
|
||||
|
@ -966,6 +1027,8 @@ static void can_stm32_remove_rx_filter(const struct device *dev, int filter_id)
|
|||
|
||||
static const struct can_driver_api can_api_funcs = {
|
||||
.get_capabilities = can_stm32_get_capabilities,
|
||||
.start = can_stm32_start,
|
||||
.stop = can_stm32_stop,
|
||||
.set_mode = can_stm32_set_mode,
|
||||
.set_timing = can_stm32_set_timing,
|
||||
.send = can_stm32_send,
|
||||
|
|
|
@ -42,6 +42,7 @@ struct can_stm32_data {
|
|||
can_state_change_callback_t state_change_cb;
|
||||
void *state_change_cb_data;
|
||||
enum can_state state;
|
||||
bool started;
|
||||
};
|
||||
|
||||
struct can_stm32_config {
|
||||
|
|
|
@ -121,6 +121,8 @@ static int can_stm32fd_init(const struct device *dev)
|
|||
|
||||
static const struct can_driver_api can_stm32fd_driver_api = {
|
||||
.get_capabilities = can_mcan_get_capabilities,
|
||||
.start = can_mcan_start,
|
||||
.stop = can_mcan_stop,
|
||||
.set_mode = can_mcan_set_mode,
|
||||
.set_timing = can_mcan_set_timing,
|
||||
.send = can_mcan_send,
|
||||
|
|
|
@ -101,6 +101,8 @@ static int can_stm32h7_init(const struct device *dev)
|
|||
|
||||
static const struct can_driver_api can_stm32h7_driver_api = {
|
||||
.get_capabilities = can_mcan_get_capabilities,
|
||||
.start = can_mcan_start,
|
||||
.stop = can_mcan_stop,
|
||||
.set_mode = can_mcan_set_mode,
|
||||
.set_timing = can_mcan_set_timing,
|
||||
.send = can_mcan_send,
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue