drivers: can: convert enum can_mode to a bit field

Convert the can_mode enum to a bit field to prepare for future extensions
(CAN-FD mode, transmitter delay compensation, one-shot mode, 3-samples
mode, ...).

Rename the existing modes:
- CAN_NORMAL_MODE   -> CAN_MODE_NORMAL
- CAN_SILENT_MODE   -> CAN_MODE_LISTENONLY
- CAN_LOOPBACK_MODE -> CAN_MODE_LOOPBACK

These mode names align with the Linux naming for CAN control modes.

The old CAN_SILENT_LOOPBACK_MODE can be set with the bitmask
(CAN_MODE_LISTENONLY | CAN_MODE_LOOPBACK).

Signed-off-by: Henrik Brix Andersen <hebad@vestas.com>
This commit is contained in:
Henrik Brix Andersen 2022-05-05 11:28:30 +02:00 committed by Carles Cufí
commit 3f97d11afd
25 changed files with 155 additions and 110 deletions

View file

@ -138,7 +138,7 @@ static inline int z_vrfy_can_get_max_filters(const struct device *dev, enum can_
}
#include <syscalls/can_get_max_filters_mrsh.c>
static inline int z_vrfy_can_set_mode(const struct device *dev, enum can_mode mode)
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));

View file

@ -197,11 +197,11 @@ static void can_loopback_remove_rx_filter(const struct device *dev, int filter_i
k_mutex_unlock(&data->mtx);
}
static int can_loopback_set_mode(const struct device *dev, enum can_mode mode)
static int can_loopback_set_mode(const struct device *dev, can_mode_t mode)
{
struct can_loopback_data *data = dev->data;
data->loopback = mode == CAN_LOOPBACK_MODE ? 1 : 0;
data->loopback = (mode & CAN_MODE_LOOPBACK) != 0 ? 1 : 0;
return 0;
}

View file

@ -240,12 +240,17 @@ int can_mcan_set_timing_data(const struct device *dev,
}
#endif /* CONFIG_CAN_FD_MODE */
int can_mcan_set_mode(const struct device *dev, enum can_mode mode)
int can_mcan_set_mode(const struct device *dev, can_mode_t mode)
{
const struct can_mcan_config *cfg = dev->config;
struct can_mcan_reg *can = cfg->can;
int ret;
if ((mode & ~(CAN_MODE_LOOPBACK | CAN_MODE_LISTENONLY)) != 0) {
LOG_ERR("unsupported mode: 0x%08x", mode);
return -ENOTSUP;
}
if (cfg->phy != NULL) {
ret = can_transceiver_enable(cfg->phy);
if (ret != 0) {
@ -269,32 +274,19 @@ int can_mcan_set_mode(const struct device *dev, enum can_mode mode)
/* Configuration Change Enable */
can->cccr |= CAN_MCAN_CCCR_CCE;
switch (mode) {
case CAN_NORMAL_MODE:
LOG_DBG("Config normal mode");
can->cccr &= ~(CAN_MCAN_CCCR_TEST | CAN_MCAN_CCCR_MON);
break;
case CAN_SILENT_MODE:
LOG_DBG("Config silent mode");
can->cccr &= ~CAN_MCAN_CCCR_TEST;
can->cccr |= CAN_MCAN_CCCR_MON;
break;
case CAN_LOOPBACK_MODE:
LOG_DBG("Config loopback mode");
can->cccr &= ~CAN_MCAN_CCCR_MON;
if ((mode & CAN_MODE_LOOPBACK) != 0) {
/* Loopback mode */
can->cccr |= CAN_MCAN_CCCR_TEST;
can->test |= CAN_MCAN_TEST_LBCK;
break;
} else {
can->cccr &= ~CAN_MCAN_CCCR_TEST;
}
case CAN_SILENT_LOOPBACK_MODE:
LOG_DBG("Config silent loopback mode");
can->cccr |= (CAN_MCAN_CCCR_TEST | CAN_MCAN_CCCR_MON);
can->test |= CAN_MCAN_TEST_LBCK;
break;
default:
break;
if ((mode & CAN_MODE_LISTENONLY) != 0) {
/* Bus monitoring mode */
can->cccr |= CAN_MCAN_CCCR_MON;
} else {
can->cccr &= ~CAN_MCAN_CCCR_MON;
}
ret = can_leave_init_mode(can, K_MSEC(CAN_INIT_TIMEOUT));

View file

@ -257,7 +257,7 @@ struct can_mcan_reg;
.custom = _custom_data, \
}
int can_mcan_set_mode(const struct device *dev, enum can_mode mode);
int can_mcan_set_mode(const struct device *dev, can_mode_t mode);
int can_mcan_set_timing(const struct device *dev,
const struct can_timing *timing);

View file

@ -440,7 +440,7 @@ done:
return ret;
}
static int mcp2515_set_mode(const struct device *dev, enum can_mode mode)
static int mcp2515_set_mode(const struct device *dev, can_mode_t mode)
{
const struct mcp2515_config *dev_cfg = dev->config;
struct mcp2515_data *dev_data = dev->data;
@ -448,13 +448,13 @@ static int mcp2515_set_mode(const struct device *dev, enum can_mode mode)
int ret;
switch (mode) {
case CAN_NORMAL_MODE:
case CAN_MODE_NORMAL:
mcp2515_mode = MCP2515_MODE_NORMAL;
break;
case CAN_SILENT_MODE:
case CAN_MODE_LISTENONLY:
mcp2515_mode = MCP2515_MODE_SILENT;
break;
case CAN_LOOPBACK_MODE:
case CAN_MODE_LOOPBACK:
mcp2515_mode = MCP2515_MODE_LOOPBACK;
break;
default:
@ -952,7 +952,7 @@ static int mcp2515_init(const struct device *dev)
return ret;
}
ret = can_set_mode(dev, CAN_NORMAL_MODE);
ret = can_set_mode(dev, CAN_MODE_NORMAL);
return ret;
}

View file

@ -179,13 +179,18 @@ static int mcux_flexcan_set_timing(const struct device *dev,
return 0;
}
static int mcux_flexcan_set_mode(const struct device *dev, enum can_mode mode)
static int mcux_flexcan_set_mode(const struct device *dev, can_mode_t mode)
{
const struct mcux_flexcan_config *config = dev->config;
uint32_t ctrl1;
uint32_t mcr;
int err;
if ((mode & ~(CAN_MODE_LOOPBACK | CAN_MODE_LISTENONLY)) != 0) {
LOG_ERR("unsupported mode: 0x%08x", mode);
return -ENOTSUP;
}
if (config->phy != NULL) {
err = can_transceiver_enable(config->phy);
if (err != 0) {
@ -199,7 +204,7 @@ static int mcux_flexcan_set_mode(const struct device *dev, enum can_mode mode)
ctrl1 = config->base->CTRL1;
mcr = config->base->MCR;
if (mode == CAN_LOOPBACK_MODE || mode == CAN_SILENT_LOOPBACK_MODE) {
if ((mode & CAN_MODE_LOOPBACK) != 0) {
/* Enable loopback and self-reception */
ctrl1 |= CAN_CTRL1_LPB_MASK;
mcr &= ~(CAN_MCR_SRXDIS_MASK);
@ -209,7 +214,7 @@ static int mcux_flexcan_set_mode(const struct device *dev, enum can_mode mode)
mcr |= CAN_MCR_SRXDIS_MASK;
}
if (mode == CAN_SILENT_MODE || mode == CAN_SILENT_LOOPBACK_MODE) {
if ((mode & CAN_MODE_LISTENONLY) != 0) {
/* Enable listen-only mode */
ctrl1 |= CAN_CTRL1_LOM_MASK;
} else {

View file

@ -566,30 +566,34 @@ static int can_rcar_enter_operation_mode(const struct can_rcar_cfg *config)
return 0;
}
static int can_rcar_set_mode(const struct device *dev, enum can_mode mode)
static int can_rcar_set_mode(const struct device *dev, can_mode_t mode)
{
const struct can_rcar_cfg *config = dev->config;
struct can_rcar_data *data = dev->data;
uint8_t tcr = 0;
int ret = 0;
if ((mode & ~(CAN_MODE_LOOPBACK | CAN_MODE_LISTENONLY)) != 0) {
LOG_ERR("Unsupported mode: 0x%08x", mode);
return -ENOTSUP;
}
k_mutex_lock(&data->inst_mutex, K_FOREVER);
switch (mode) {
case CAN_NORMAL_MODE:
tcr = 0;
break;
/*Controller is not allowed to send dominant bits*/
case CAN_SILENT_MODE:
tcr = RCAR_CAN_TCR_LISTEN_ONLY | RCAR_CAN_TCR_TSTE;
break;
/*Controller is in loopback mode (receive own messages)*/
case CAN_LOOPBACK_MODE:
tcr = RCAR_CAN_TCR_INT_LOOP | RCAR_CAN_TCR_TSTE;
break;
/*Combination of loopback and silent*/
case CAN_SILENT_LOOPBACK_MODE:
if ((mode & (CAN_MODE_LOOPBACK | CAN_MODE_LISTENONLY)) ==
(CAN_MODE_LOOPBACK | CAN_MODE_LISTENONLY)) {
LOG_ERR("Combination of loopback and listenonly modes not supported");
ret = -ENOTSUP;
goto unlock;
} else if ((mode & CAN_MODE_LOOPBACK) != 0) {
/* Loopback mode */
tcr = RCAR_CAN_TCR_INT_LOOP | RCAR_CAN_TCR_TSTE;
} else if ((mode & CAN_MODE_LISTENONLY) != 0) {
/* Listen-only mode */
tcr = RCAR_CAN_TCR_LISTEN_ONLY | RCAR_CAN_TCR_TSTE;
} else {
/* Normal mode */
tcr = 0;
}
/* Enable CAN transceiver */
@ -957,7 +961,7 @@ static int can_rcar_init(const struct device *dev)
return ret;
}
ret = can_rcar_set_mode(dev, CAN_NORMAL_MODE);
ret = can_rcar_set_mode(dev, CAN_MODE_NORMAL);
if (ret) {
return ret;
}

View file

@ -20,7 +20,7 @@ static struct k_poll_event msgq_events[1] = {
};
static inline int read_config_options(const struct shell *sh, int pos,
char **argv, bool *silent, bool *loopback)
char **argv, bool *listenonly, bool *loopback)
{
char *arg = argv[pos];
@ -31,10 +31,10 @@ static inline int read_config_options(const struct shell *sh, int pos,
for (arg = &arg[1]; *arg; arg++) {
switch (*arg) {
case 's':
if (silent == NULL) {
if (listenonly == NULL) {
shell_error(sh, "Unknown option %c", *arg);
} else {
*silent = true;
*listenonly = true;
}
break;
case 'l':
@ -231,8 +231,8 @@ static int cmd_config(const struct shell *sh, size_t argc, char **argv)
{
const struct device *can_dev;
int pos = 1;
bool silent = false, loopback = false;
enum can_mode mode;
bool listenonly = false, loopback = false;
can_mode_t mode = CAN_MODE_NORMAL;
uint32_t bitrate;
int ret;
@ -245,19 +245,17 @@ static int cmd_config(const struct shell *sh, size_t argc, char **argv)
pos++;
pos = read_config_options(sh, pos, argv, &silent, &loopback);
pos = read_config_options(sh, pos, argv, &listenonly, &loopback);
if (pos < 0) {
return -EINVAL;
}
if (silent && loopback) {
mode = CAN_SILENT_LOOPBACK_MODE;
} else if (silent) {
mode = CAN_SILENT_MODE;
} else if (loopback) {
mode = CAN_LOOPBACK_MODE;
} else {
mode = CAN_NORMAL_MODE;
if (listenonly) {
mode |= CAN_MODE_LISTENONLY;
}
if (loopback) {
mode |= CAN_MODE_LOOPBACK;
}
ret = can_set_mode(can_dev, mode);
@ -447,8 +445,8 @@ SHELL_STATIC_SUBCMD_SET_CREATE(sub_can,
SHELL_CMD_ARG(config, NULL,
"Configure CAN controller.\n"
" Usage: config device_name [-sl] bitrate\n"
" -s Silent mode\n"
" -l Listen-only mode",
" -s Listen-only mode\n"
" -l Loopback mode",
cmd_config, 3, 1),
SHELL_CMD_ARG(send, NULL,
"Send a CAN frame.\n"

View file

@ -341,7 +341,7 @@ static int can_leave_sleep_mode(CAN_TypeDef *can)
return 0;
}
static int can_stm32_set_mode(const struct device *dev, enum can_mode mode)
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;
@ -350,6 +350,11 @@ static int can_stm32_set_mode(const struct device *dev, enum can_mode mode)
LOG_DBG("Set mode %d", mode);
if ((mode & ~(CAN_MODE_LOOPBACK | CAN_MODE_LISTENONLY)) != 0) {
LOG_ERR("unsupported mode: 0x%08x", mode);
return -ENOTSUP;
}
k_mutex_lock(&data->inst_mutex, K_FOREVER);
if (cfg->phy != NULL) {
@ -366,23 +371,18 @@ static int can_stm32_set_mode(const struct device *dev, enum can_mode mode)
goto done;
}
switch (mode) {
case CAN_NORMAL_MODE:
can->BTR &= ~(CAN_BTR_LBKM | CAN_BTR_SILM);
break;
case CAN_LOOPBACK_MODE:
can->BTR &= ~(CAN_BTR_SILM);
if ((mode & CAN_MODE_LOOPBACK) != 0) {
/* Loopback mode */
can->BTR |= CAN_BTR_LBKM;
break;
case CAN_SILENT_MODE:
can->BTR &= ~(CAN_BTR_LBKM);
} else {
can->BTR &= ~CAN_BTR_LBKM;
}
if ((mode & CAN_MODE_LISTENONLY) != 0) {
/* Silent mode */
can->BTR |= CAN_BTR_SILM;
break;
case CAN_SILENT_LOOPBACK_MODE:
can->BTR |= CAN_BTR_LBKM | CAN_BTR_SILM;
break;
default:
break;
} else {
can->BTR &= ~CAN_BTR_SILM;
}
done:
@ -568,7 +568,7 @@ static int can_stm32_init(const struct device *dev)
return ret;
}
ret = can_stm32_set_mode(dev, CAN_NORMAL_MODE);
ret = can_stm32_set_mode(dev, CAN_MODE_NORMAL);
if (ret) {
return ret;
}

View file

@ -79,18 +79,32 @@ extern "C" {
/** @} */
/**
* @brief Defines the mode of the CAN controller
* @name CAN controller mode flags
* @anchor CAN_MODE_FLAGS
*
* @{
*/
enum can_mode {
/** Normal mode. */
CAN_NORMAL_MODE,
/** Controller is not allowed to send dominant bits. */
CAN_SILENT_MODE,
#define CAN_MODE_NORMAL 0
/** Controller is in loopback mode (receives own frames). */
CAN_LOOPBACK_MODE,
/** Combination of loopback and silent modes. */
CAN_SILENT_LOOPBACK_MODE
};
#define CAN_MODE_LOOPBACK BIT(0)
/** Controller is not allowed to send dominant bits. */
#define CAN_MODE_LISTENONLY BIT(1)
/** @} */
/**
* @brief Provides a type to hold CAN controller configuration flags.
*
* The lower 24 bits are reserved for common CAN controller mode flags. The upper 8 bits are
* reserved for CAN controller/driver specific flags.
*
* @see @ref CAN_MODE_FLAGS.
*/
typedef uint32_t can_mode_t;
/**
* @brief Defines the state of the CAN bus
@ -310,7 +324,7 @@ typedef int (*can_set_timing_data_t)(const struct device *dev,
* @brief Callback API upon setting CAN controller mode
* See @a can_set_mode() for argument description
*/
typedef int (*can_set_mode_t)(const struct device *dev, enum can_mode mode);
typedef int (*can_set_mode_t)(const struct device *dev, can_mode_t mode);
/**
* @brief Callback API upon sending a CAN frame
@ -891,9 +905,9 @@ static inline int z_impl_can_set_timing(const struct device *dev,
* @retval 0 If successful.
* @retval -EIO General input/output error, failed to configure device.
*/
__syscall int can_set_mode(const struct device *dev, enum can_mode mode);
__syscall int can_set_mode(const struct device *dev, can_mode_t mode);
static inline int z_impl_can_set_mode(const struct device *dev, enum can_mode mode)
static inline int z_impl_can_set_mode(const struct device *dev, can_mode_t mode)
{
const struct can_driver_api *api = (const struct can_driver_api *)dev->api;

View file

@ -229,7 +229,7 @@ CO_ReturnError_t CO_CANmodule_init(CO_CANmodule_t *CANmodule,
return CO_ERROR_ILLEGAL_ARGUMENT;
}
err = can_set_mode(CANmodule->dev, CAN_NORMAL_MODE);
err = can_set_mode(CANmodule->dev, CAN_MODE_NORMAL);
if (err) {
LOG_ERR("failed to configure CAN interface (err %d)", err);
return CO_ERROR_ILLEGAL_ARGUMENT;
@ -250,7 +250,7 @@ void CO_CANmodule_disable(CO_CANmodule_t *CANmodule)
canopen_detach_all_rx_filters(CANmodule);
err = can_set_mode(CANmodule->dev, CAN_SILENT_MODE);
err = can_set_mode(CANmodule->dev, CAN_MODE_LISTENONLY);
if (err) {
LOG_ERR("failed to disable CAN interface (err %d)", err);
}

View file

@ -220,7 +220,11 @@ void main(void)
}
#ifdef CONFIG_LOOPBACK_MODE
can_set_mode(can_dev, CAN_LOOPBACK_MODE);
ret = can_set_mode(can_dev, CAN_MODE_LOOPBACK);
if (ret != 0) {
printk("Error setting CAN mode [%d]", ret);
return;
}
#endif
if (led.port != NULL) {

View file

@ -181,7 +181,7 @@ static int setup_socket(void)
}
#ifdef CONFIG_SAMPLE_SOCKETCAN_LOOPBACK_MODE
can_set_mode(DEVICE_DT_GET(DT_CHOSEN(zephyr_canbus)), CAN_LOOPBACK_MODE);
can_set_mode(DEVICE_DT_GET(DT_CHOSEN(zephyr_canbus)), CAN_MODE_LOOPBACK);
#endif
fd = socket(AF_CAN, SOCK_RAW, CAN_RAW);

View file

@ -22,6 +22,10 @@
#include <stm32f0xx.h>
/* The STM32 HAL headers define these, but they conflict with the Zephyr can.h */
#undef CAN_MODE_NORMAL
#undef CAN_MODE_LOOPBACK
/* Add generated devicetree information and STM32 helper macros */
#include <st_stm32_dt.h>

View file

@ -22,6 +22,10 @@
#include <stm32f1xx.h>
/* The STM32 HAL headers define these, but they conflict with the Zephyr can.h */
#undef CAN_MODE_NORMAL
#undef CAN_MODE_LOOPBACK
/* Add generated devicetree information and STM32 helper macros */
#include <st_stm32_dt.h>

View file

@ -21,6 +21,10 @@
#include <stm32f2xx.h>
/* The STM32 HAL headers define these, but they conflict with the Zephyr can.h */
#undef CAN_MODE_NORMAL
#undef CAN_MODE_LOOPBACK
/* Add generated devicetree information and STM32 helper macros */
#include <st_stm32_dt.h>

View file

@ -23,6 +23,10 @@
#include <stm32f3xx.h>
/* The STM32 HAL headers define these, but they conflict with the Zephyr can.h */
#undef CAN_MODE_NORMAL
#undef CAN_MODE_LOOPBACK
/* Add generated devicetree information and STM32 helper macros */
#include <st_stm32_dt.h>

View file

@ -22,6 +22,10 @@
#include <stm32f4xx.h>
/* The STM32 HAL headers define these, but they conflict with the Zephyr can.h */
#undef CAN_MODE_NORMAL
#undef CAN_MODE_LOOPBACK
/* Add generated devicetree information and STM32 helper macros */
#include <st_stm32_dt.h>

View file

@ -21,6 +21,10 @@
#include <stm32f7xx.h>
/* The STM32 HAL headers define these, but they conflict with the Zephyr can.h */
#undef CAN_MODE_NORMAL
#undef CAN_MODE_LOOPBACK
/* Add generated devicetree information and STM32 helper macros */
#include <st_stm32_dt.h>

View file

@ -23,6 +23,10 @@
#include <stm32l4xx.h>
/* The STM32 HAL headers define these, but they conflict with the Zephyr can.h */
#undef CAN_MODE_NORMAL
#undef CAN_MODE_LOOPBACK
/* Add generated devicetree information and STM32 helper macros */
#include <st_stm32_dt.h>

View file

@ -661,7 +661,7 @@ static void test_set_loopback(void)
{
int err;
err = can_set_mode(can_dev, CAN_LOOPBACK_MODE);
err = can_set_mode(can_dev, CAN_MODE_LOOPBACK);
zassert_equal(err, 0, "failed to set loopback-mode (err %d)", err);
}
@ -953,10 +953,10 @@ static void test_filters_preserved_through_mode_change(void)
zassert_equal(err, 0, "receive timeout");
assert_frame_equal(&frame, &test_std_frame_1, 0);
err = can_set_mode(can_dev, CAN_NORMAL_MODE);
err = can_set_mode(can_dev, CAN_MODE_NORMAL);
zassert_equal(err, 0, "failed to set normal mode (err %d)", err);
err = can_set_mode(can_dev, CAN_LOOPBACK_MODE);
err = can_set_mode(can_dev, CAN_MODE_LOOPBACK);
zassert_equal(err, 0, "failed to set loopback-mode (err %d)", err);
send_test_frame(can_dev, &test_std_frame_1);

View file

@ -348,7 +348,7 @@ static void test_set_loopback(void)
{
int err;
err = can_set_mode(can_dev, CAN_LOOPBACK_MODE);
err = can_set_mode(can_dev, CAN_MODE_LOOPBACK);
zassert_equal(err, 0, "failed to set loopback-mode (err %d)", err);
}

View file

@ -146,7 +146,7 @@ static void test_filter_handling(void)
zassert_true(device_is_ready(dev), "CAN device not ready");
/* Set driver to loopback mode */
err = can_set_mode(dev, CAN_LOOPBACK_MODE);
err = can_set_mode(dev, CAN_MODE_LOOPBACK);
zassert_equal(err, 0, "failed to set loopback mode");
/* Add a extended and masked filter (1 bank/filter) */

View file

@ -969,7 +969,7 @@ void test_main(void)
zassert_true(device_is_ready(can_dev), "CAN device not ready");
ret = can_set_mode(can_dev, CAN_LOOPBACK_MODE);
ret = can_set_mode(can_dev, CAN_MODE_LOOPBACK);
zassert_equal(ret, 0, "Failed to set loopback mode [%d]", ret);
k_sem_init(&send_compl_sem, 0, 1);

View file

@ -420,7 +420,7 @@ void test_main(void)
zassert_true(device_is_ready(can_dev), "CAN device not ready");
ret = can_set_mode(can_dev, CAN_LOOPBACK_MODE);
ret = can_set_mode(can_dev, CAN_MODE_LOOPBACK);
zassert_equal(ret, 0, "Configuring loopback mode failed (%d)", ret);
ztest_test_suite(isotp,