canbus: Convert canbus driver and subsys to new timeout API
Convert all canbus related API/samples/tests/subsys to the new timeout API with k_timeout_t. Signed-off-by: Alexander Wachter <alexander@wachter.cloud>
This commit is contained in:
parent
637dd67c66
commit
464f135ce6
21 changed files with 98 additions and 100 deletions
|
@ -8,7 +8,6 @@
|
|||
#
|
||||
menuconfig CAN
|
||||
bool "CAN Drivers"
|
||||
select LEGACY_TIMEOUT_API
|
||||
help
|
||||
Enable CAN Driver Configuration
|
||||
|
||||
|
|
|
@ -20,7 +20,7 @@ static inline int z_vrfy_can_configure(struct device *dev, enum can_mode mode,
|
|||
|
||||
static inline int z_vrfy_can_send(struct device *dev,
|
||||
const struct zcan_frame *msg,
|
||||
s32_t timeout,
|
||||
k_timeout_t timeout,
|
||||
can_tx_callback_t callback_isr,
|
||||
void *callback_arg)
|
||||
{
|
||||
|
@ -37,7 +37,8 @@ static inline int z_vrfy_can_send(struct device *dev,
|
|||
|
||||
return z_impl_can_send((struct device *)dev,
|
||||
(const struct zcan_frame *)msg,
|
||||
(s32_t)timeout, (can_tx_callback_t) callback_isr,
|
||||
(k_timeout_t)timeout,
|
||||
(can_tx_callback_t) callback_isr,
|
||||
(void *)callback_arg);
|
||||
}
|
||||
#include <syscalls/can_send_mrsh.c>
|
||||
|
@ -84,12 +85,12 @@ enum can_state z_vrfy_can_get_state(struct device *dev,
|
|||
|
||||
|
||||
#ifndef CONFIG_CAN_AUTO_BUS_OFF_RECOVERY
|
||||
static inline int z_vrfy_can_recover(struct device *dev, s32_t timeout)
|
||||
static inline int z_vrfy_can_recover(struct device *dev, k_timeout_t timeout)
|
||||
{
|
||||
|
||||
Z_OOPS(Z_SYSCALL_OBJ(dev, K_OBJ_DRIVER_CAN));
|
||||
|
||||
return z_impl_can_recover(dev, s32_t timeout);
|
||||
return z_impl_can_recover(dev, k_timeout_t timeout);
|
||||
}
|
||||
#include <syscalls/can_recover_mrsh.c>
|
||||
#endif /* CONFIG_CAN_AUTO_BUS_OFF_RECOVERY */
|
||||
|
|
|
@ -89,7 +89,7 @@ void tx_thread(void *data_arg, void *arg2, void *arg3)
|
|||
}
|
||||
|
||||
int can_loopback_send(struct device *dev, const struct zcan_frame *frame,
|
||||
s32_t timeout, can_tx_callback_t callback,
|
||||
k_timeout_t timeout, can_tx_callback_t callback,
|
||||
void *callback_arg)
|
||||
{
|
||||
struct can_loopback_data *data = DEV_DATA(dev);
|
||||
|
@ -217,7 +217,7 @@ static enum can_state can_loopback_get_state(struct device *dev,
|
|||
}
|
||||
|
||||
#ifndef CONFIG_CAN_AUTO_BUS_OFF_RECOVERY
|
||||
int can_loopback_recover(struct device *dev, s32_t timeout)
|
||||
int can_loopback_recover(struct device *dev, k_timeout_t timeout)
|
||||
{
|
||||
ARG_UNUSED(dev);
|
||||
ARG_UNUSED(timeout);
|
||||
|
|
|
@ -382,7 +382,8 @@ done:
|
|||
}
|
||||
|
||||
static int mcp2515_send(struct device *dev, const struct zcan_frame *msg,
|
||||
s32_t timeout, can_tx_callback_t callback, void *callback_arg)
|
||||
k_timeout_t timeout, can_tx_callback_t callback,
|
||||
void *callback_arg)
|
||||
{
|
||||
struct mcp2515_data *dev_data = DEV_DATA(dev);
|
||||
u8_t tx_idx = 0U;
|
||||
|
@ -392,7 +393,8 @@ static int mcp2515_send(struct device *dev, const struct zcan_frame *msg,
|
|||
u8_t tx_frame[MCP2515_FRAME_LEN];
|
||||
|
||||
if (msg->dlc > CAN_MAX_DLC) {
|
||||
LOG_ERR("DLC of %d exceeds maximum (%d)", msg->dlc, CAN_MAX_DLC);
|
||||
LOG_ERR("DLC of %d exceeds maximum (%d)",
|
||||
msg->dlc, CAN_MAX_DLC);
|
||||
return CAN_TX_EINVAL;
|
||||
}
|
||||
|
||||
|
@ -630,7 +632,7 @@ static void mcp2515_handle_errors(struct device *dev)
|
|||
}
|
||||
|
||||
#ifndef CONFIG_CAN_AUTO_BUS_OFF_RECOVERY
|
||||
static void mcp2515_recover(struct device *dev, s32_t timeout)
|
||||
static void mcp2515_recover(struct device *dev, k_timeout_t timeout)
|
||||
{
|
||||
ARG_UNUSED(dev);
|
||||
ARG_UNUSED(timeout);
|
||||
|
|
|
@ -246,8 +246,8 @@ static int mcux_get_tx_alloc(struct mcux_flexcan_data *data)
|
|||
}
|
||||
|
||||
static int mcux_flexcan_send(struct device *dev, const struct zcan_frame *msg,
|
||||
s32_t timeout, can_tx_callback_t callback_isr,
|
||||
void *callback_arg)
|
||||
k_timeout_t timeout,
|
||||
can_tx_callback_t callback_isr, void *callback_arg)
|
||||
{
|
||||
const struct mcux_flexcan_config *config = dev->config->config_info;
|
||||
struct mcux_flexcan_data *data = dev->driver_data;
|
||||
|
@ -384,7 +384,7 @@ static enum can_state mcux_flexcan_get_state(struct device *dev,
|
|||
}
|
||||
|
||||
#ifndef CONFIG_CAN_AUTO_BUS_OFF_RECOVERY
|
||||
int mcux_flexcan_recover(struct device *dev, s32_t timeout)
|
||||
int mcux_flexcan_recover(struct device *dev, k_timeout_t timeout)
|
||||
{
|
||||
const struct mcux_flexcan_config *config = dev->config->config_info;
|
||||
int ret = 0;
|
||||
|
@ -394,13 +394,13 @@ int mcux_flexcan_recover(struct device *dev, s32_t timeout)
|
|||
return 0;
|
||||
}
|
||||
|
||||
start_time = k_uptime_get();
|
||||
start_time = k_uptime_ticks();
|
||||
config->base->CTRL1 &= ~CAN_CTRL1_BOFFREC_MASK;
|
||||
|
||||
if (timeout != K_NO_WAIT) {
|
||||
while (mcux_flexcan_get_state(dev, NULL) == CAN_BUS_OFF) {
|
||||
if (timeout != K_FOREVER &&
|
||||
k_uptime_get() - start_time >= timeout) {
|
||||
k_uptime_ticks() - start_time >= timeout.ticks) {
|
||||
ret = CAN_TIMEOUT;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -89,7 +89,7 @@ static inline void can_set_lladdr(struct net_pkt *pkt, struct zcan_frame *frame)
|
|||
}
|
||||
|
||||
static int net_can_send(struct device *dev, const struct zcan_frame *frame,
|
||||
can_tx_callback_t cb, void *cb_arg, s32_t timeout)
|
||||
can_tx_callback_t cb, void *cb_arg, k_timeout_t timeout)
|
||||
{
|
||||
struct net_can_context *ctx = dev->driver_data;
|
||||
|
||||
|
|
|
@ -297,7 +297,7 @@ static int cmd_send(const struct shell *shell, size_t argc, char **argv)
|
|||
ext ? frame.ext_id : frame.std_id,
|
||||
ext ? "extended" : "standard", frame.dlc);
|
||||
|
||||
ret = can_send(can_dev, &frame, SYS_FOREVER_MS, NULL, NULL);
|
||||
ret = can_send(can_dev, &frame, K_FOREVER, NULL, NULL);
|
||||
if (ret) {
|
||||
shell_error(shell, "Failed to send frame [%d]", ret);
|
||||
return -EIO;
|
||||
|
|
|
@ -19,7 +19,6 @@
|
|||
LOG_MODULE_DECLARE(can_driver, CONFIG_CAN_LOG_LEVEL);
|
||||
|
||||
#define CAN_INIT_TIMEOUT (10 * sys_clock_hw_cycles_per_sec() / MSEC_PER_SEC)
|
||||
#define CAN_BOFF_RECOVER_TIMEOUT (10 * sys_clock_hw_cycles_per_sec() / MSEC_PER_SEC)
|
||||
|
||||
#if DT_HAS_NODE(DT_NODELABEL(can1)) && \
|
||||
DT_NODE_HAS_COMPAT(DT_NODELABEL(can1), st_stm32_can) && \
|
||||
|
@ -503,13 +502,13 @@ static enum can_state can_stm32_get_state(struct device *dev,
|
|||
}
|
||||
|
||||
#ifndef CONFIG_CAN_AUTO_BUS_OFF_RECOVERY
|
||||
int can_stm32_recover(struct device *dev, s32_t timeout)
|
||||
int can_stm32_recover(struct device *dev, k_timeout_t timeout)
|
||||
{
|
||||
const struct can_stm32_config *cfg = DEV_CFG(dev);
|
||||
struct can_stm32_data *data = DEV_DATA(dev);
|
||||
CAN_TypeDef *can = cfg->can;
|
||||
int ret = CAN_TIMEOUT;
|
||||
u32_t start_time;
|
||||
s64_t start_time;
|
||||
|
||||
if (!(can->ESR & CAN_ESR_BOFF)) {
|
||||
return 0;
|
||||
|
@ -526,10 +525,11 @@ int can_stm32_recover(struct device *dev, s32_t timeout)
|
|||
|
||||
can_leave_init_mode(can);
|
||||
|
||||
start_time = k_cycle_get_32();
|
||||
start_time = k_uptime_ticks();
|
||||
|
||||
while (can->ESR & CAN_ESR_BOFF) {
|
||||
if (k_cycle_get_32() - start_time >= CAN_BOFF_RECOVER_TIMEOUT) {
|
||||
if (timeout != K_FOREVER &&
|
||||
k_uptime_ticks() - start_time >= timeout.ticks) {
|
||||
goto done;
|
||||
}
|
||||
}
|
||||
|
@ -544,7 +544,8 @@ done:
|
|||
|
||||
|
||||
int can_stm32_send(struct device *dev, const struct zcan_frame *msg,
|
||||
s32_t timeout, can_tx_callback_t callback, void *callback_arg)
|
||||
k_timeout_t timeout, can_tx_callback_t callback,
|
||||
void *callback_arg)
|
||||
{
|
||||
const struct can_stm32_config *cfg = DEV_CFG(dev);
|
||||
struct can_stm32_data *data = DEV_DATA(dev);
|
||||
|
@ -578,8 +579,7 @@ int can_stm32_send(struct device *dev, const struct zcan_frame *msg,
|
|||
k_mutex_lock(&data->inst_mutex, K_FOREVER);
|
||||
while (!(transmit_status_register & CAN_TSR_TME)) {
|
||||
k_mutex_unlock(&data->inst_mutex);
|
||||
LOG_DBG("Transmit buffer full. Wait with timeout (%dms)",
|
||||
timeout);
|
||||
LOG_DBG("Transmit buffer full");
|
||||
if (k_sem_take(&data->tx_int_sem, timeout)) {
|
||||
return CAN_TIMEOUT;
|
||||
}
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue