--- cpukit/dev/can/can.c | 514 +++++++++++++++++++++++++++++ cpukit/include/dev/can/can-msg.h | 55 +++ cpukit/include/dev/can/can-queue.h | 127 +++++++ cpukit/include/dev/can/can.h | 102 ++++++ spec/build/cpukit/librtemscpu.yml | 6 + 5 files changed, 804 insertions(+) create mode 100644 cpukit/dev/can/can.c create mode 100644 cpukit/include/dev/can/can-msg.h create mode 100644 cpukit/include/dev/can/can-queue.h create mode 100644 cpukit/include/dev/can/can.h
diff --git a/cpukit/dev/can/can.c b/cpukit/dev/can/can.c new file mode 100644 index 0000000000..8feec8800b --- /dev/null +++ b/cpukit/dev/can/can.c @@ -0,0 +1,514 @@ +/* SPDX-License-Identifier: BSD-2-Clause */ + +/** + * @file + * + * @ingroup CANBus + * + * @brief Controller Area Network (CAN) Bus Implementation + * + */ + +/* + * Copyright (C) 2022 Prashanth S (fishesprasha...@gmail.com) + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include <rtems/imfs.h> +#include <rtems/thread.h> + +#include <dev/can/can-queue.h> +#include <dev/can/can.h> + +#include <string.h> +#include <stdlib.h> + +#include <fcntl.h> + +static ssize_t +can_bus_open(rtems_libio_t *iop, const char *path, int oflag, mode_t mode); +static ssize_t +can_bus_read(rtems_libio_t *iop, void *buffer, size_t count); +static ssize_t +can_bus_write(rtems_libio_t *iop, const void *buffer, size_t count); +static ssize_t +can_bus_ioctl(rtems_libio_t *iop, ioctl_command_t request, void *buffer); + +static int can_xmit(struct can_bus *bus); + +static int can_create_sem(struct can_bus *); +static int try_sem(struct can_bus *); +static int take_sem(struct can_bus *); +static int give_sem(struct can_bus *); + +/* sem_count this is for debug purpose, for debugging +the take_sem and give_sem +*/ +static int sem_count = 0; + +static void can_bus_obtain(can_bus *bus) +{ + rtems_recursive_mutex_lock(&bus->mutex); +} + +static void can_bus_release(can_bus *bus) +{ + rtems_recursive_mutex_unlock(&bus->mutex); +} + +int can_create_sem(struct can_bus *bus) +{ + int ret = 0; + + ret = rtems_semaphore_create(rtems_build_name('c', 'a', 'n', bus->index), + CAN_TX_BUF_COUNT, RTEMS_FIFO | RTEMS_COUNTING_SEMAPHORE | RTEMS_LOCAL, + 0, &bus->tx_fifo_sem_id); + + if (ret != 0) { + printf("can_create_sem: rtems_semaphore_create failed %d\n", ret); + } + + return ret; +} + +static void can_interrupt_lock_acquire(struct can_bus *bus) +{ + can_bus_obtain(bus); + bus->can_dev_ops->dev_int(bus->priv, false); +} + +static void can_interrupt_lock_release(struct can_bus *bus) +{ + bus->can_dev_ops->dev_int(bus->priv, true); + can_bus_release(bus); +} + +static int take_sem(struct can_bus *bus) +{ + int ret = rtems_semaphore_obtain(bus->tx_fifo_sem_id, RTEMS_WAIT, + RTEMS_NO_TIMEOUT); + if (ret == RTEMS_SUCCESSFUL) { + CAN_DEBUG_LOCK("take_sem: Counting semaphore count = %d\n", ++sem_count); + if (sem_count > CAN_TX_BUF_COUNT) { + printf("take_sem error: sem_count is misleading\n"); + while (1); + } + } + + return ret; +} + +static int give_sem(struct can_bus *bus) +{ + int ret = rtems_semaphore_release(bus->tx_fifo_sem_id); + if (ret == RTEMS_SUCCESSFUL) { + CAN_DEBUG_LOCK("give_sem: Counting semaphore count = %d\n", --sem_count); + if (sem_count < 0) { + printf("give_sem error: sem_count is misleading\n"); + while (1); + } + } + + return ret; +} + +static int try_sem(struct can_bus *bus) +{ + int ret = rtems_semaphore_obtain(bus->tx_fifo_sem_id, RTEMS_NO_WAIT, + RTEMS_NO_TIMEOUT); + if (ret == RTEMS_SUCCESSFUL) { + CAN_DEBUG_LOCK("take_sem: Counting semaphore count = %d\n", ++sem_count); + if (sem_count > CAN_TX_BUF_COUNT) { + printf("take_sem error: sem_count is misleading\n"); + while (1); + } + } + + return ret; +} + +static ssize_t +can_bus_open(rtems_libio_t *iop, const char *path, int oflag, mode_t mode) +{ +/* + can_bus *bus = IMFS_generic_get_context_by_iop(iop); + + if (bus == NULL) { + return -RTEMS_NOT_DEFINED; + } +*/ + return 0; +} + +int can_receive(struct can_bus *bus, struct can_msg *msg) +{ + int32_t ret = 0; + + uint32_t count = 0; + + ret = rtems_message_queue_broadcast(bus->rx_queue_id, msg, CAN_MSGLEN(msg), + &count); + if (ret != RTEMS_SUCCESSFUL) { + CAN_DEBUG_RX("rtems_message_queue_send failed\n"); + } + + CAN_DEBUG_RX("rtems_message_queue_broadcast = %u\n", count); + + return ret; +} + +/* count argument is not used here as struct can_msg has the dlc member */ +static ssize_t can_bus_read(rtems_libio_t *iop, void *buffer, size_t count) +{ + int32_t ret = 0; + uint32_t flags = 0; + + can_bus *bus = IMFS_generic_get_context_by_iop(iop); + + if (bus == NULL || bus->can_dev_ops->dev_rx == NULL) { + return -RTEMS_NOT_DEFINED; + } + + struct can_msg *msg = (struct can_msg *)buffer; + + if ((iop->flags & O_NONBLOCK) != 0) { + flags = RTEMS_NO_WAIT; + } + + ret = rtems_message_queue_receive(bus->rx_queue_id, (void *)msg, &count, + flags, 0); + if (ret != RTEMS_SUCCESSFUL) { + return ret; + } + + return count; +} + +static int can_xmit(struct can_bus *bus) +{ + int ret = RTEMS_SUCCESSFUL; + + struct can_msg *msg = NULL; + + while (1) { + CAN_DEBUG_LOCK("can_xmit: acquiring lock\n"); + can_interrupt_lock_acquire(bus); + + ret = bus->can_dev_ops->dev_tx_ready(bus->priv); + if (ret != true) { + goto return_with_lock_release; + } + + msg = can_tx_get_data_buf(bus); + if (msg == NULL) { + goto return_with_lock_release; + } + + ret = bus->can_dev_ops->dev_tx(bus->priv, msg); + if (ret != RTEMS_SUCCESSFUL) { + printf("can_xmit: dev_send failed\n"); + } + + ret = give_sem(bus); + if (ret != RTEMS_SUCCESSFUL) { + printf("can_tx_done: rtems_semaphore_release failed = %d\n", ret); + } + + CAN_DEBUG_LOCK("can_xmit: releasing lock\n"); + can_interrupt_lock_release(bus); + + //can_tx_done(bus); + } + + return ret; + +return_with_lock_release: + + CAN_DEBUG_LOCK("can_xmit: releasing lock\n"); + can_interrupt_lock_release(bus); + + return ret; +} + +void can_print_msg(struct can_msg const *msg) +{ + printf("\n----------------------------------------------------------------\n"); + printf("id = %d len = %d flags = 0x%08X\n", msg->id, msg->len, msg->flags); + + for (int i = 0; i < msg->len; i++) { + printf("%02x ", msg->data[i]); + } + + printf("\n-----------------------------------------------------------------\n"); +} + +/* can_tx_done should be called only with interrupts disabled */ +int can_tx_done(struct can_bus *bus) +{ + int ret = 0; + + if (bus->can_dev_ops->dev_tx_ready(bus->priv) == true) { + can_xmit(bus); + } + + return ret; +} + +static ssize_t +can_bus_write(rtems_libio_t *iop, const void *buffer, size_t count) +{ + can_bus *bus = IMFS_generic_get_context_by_iop(iop); + + if (bus == NULL || bus->can_dev_ops->dev_tx == NULL) { + return -RTEMS_NOT_DEFINED; + } + + int32_t ret = 0; + + struct can_msg const *msg = buffer; + struct can_msg *fifo_buf = NULL; + + CAN_DEBUG_LOCK("can_bus_write: acquiring lock tx_fifo.empty_count\n"); + can_interrupt_lock_acquire(bus); + CAN_DEBUG_TX("can_bus_write: empty_count = %u\n", bus->tx_fifo.empty_count); + CAN_DEBUG_LOCK("can_bus_write: release lock tx_fifo.empty_count\n"); + can_interrupt_lock_release(bus); + + if ((iop->flags & O_NONBLOCK) != 0) { + ret = try_sem(bus); + if (ret != RTEMS_SUCCESSFUL) { + return -RTEMS_NO_MEMORY; + } + } else { + CAN_DEBUG_LOCK("can_bus_write: acquiring lock can_tx_buf_waiters++\n"); + can_interrupt_lock_acquire(bus); + bus->can_tx_buf_waiters++; + CAN_DEBUG_LOCK("can_bus_write: release lock can_tx_buf_waiters++\n"); + can_interrupt_lock_release(bus); + + ret = take_sem(bus); + + CAN_DEBUG_LOCK("can_bus_write: acquiring lock can_tx_buf_waiters--\n"); + can_interrupt_lock_acquire(bus); + bus->can_tx_buf_waiters--; + CAN_DEBUG_LOCK("can_bus_write: release lock can_tx_buf_waiters--\n"); + can_interrupt_lock_release(bus); + + if (ret != RTEMS_SUCCESSFUL) { + printf("can_bus_write: cannot take semaphore\n"); + ret = -RTEMS_INTERNAL_ERROR; + goto return_from_func; + } + } + + /* sleep is for debug purpose to test concurrency issues */ + printf("can_bus_write: calling sleep\n"); + sleep(1); + printf("can_bus_write: coming out sleep\n"); + + CAN_DEBUG_LOCK("can_bus_write: acquiring lock can_tx_get_empty_buf\n"); + can_interrupt_lock_acquire(bus); + fifo_buf = can_tx_get_empty_buf(bus); + CAN_DEBUG_LOCK("can_bus_write: releasing lock can_tx_get_empty_buf\n"); + can_interrupt_lock_release(bus); + + if (fifo_buf == NULL) { + printf("can_bus_write: Buffer counts are not synchronized with semaphore count\n"); + return -RTEMS_INTERNAL_ERROR; + } + + /* sleep is for debug purpose to test concurrency issues */ + printf("can_bus_write: calling sleep\n"); + sleep(1); + printf("can_bus_write: coming out sleep\n"); + + uint32_t msg_size = (char *)&msg->data[msg->len] - (char *)msg; + + CAN_DEBUG_TX("can_bus_write: can_msg_size = %u\n", msg_size); + if (msg_size > sizeof(struct can_msg)) { + printf("can_bus_write:" + "can message len error msg_size = %u struct can_msg = %u\n", + msg_size, sizeof(struct can_msg)); + return -RTEMS_INVALID_SIZE; + } + + CAN_DEBUG_TX("can_bus_write: copying msg from application to driver buffer\n"); + memcpy(fifo_buf, msg, msg_size); + ret = msg_size; + + /* sleep is for debug purpose to test concurrency issues */ + printf("can_bus_write: calling sleep\n"); + sleep(1); + printf("can_bus_write: coming out sleep\n"); + + if (bus->can_dev_ops->dev_tx_ready(bus->priv) == true) { + can_xmit(bus); + } + +return_from_func: + return ret; +} + +static ssize_t +can_bus_ioctl(rtems_libio_t *iop, ioctl_command_t request, void *buffer) +{ + can_bus *bus = IMFS_generic_get_context_by_iop(iop); + + if (bus == NULL || bus->can_dev_ops->dev_ioctl == NULL) { + return -RTEMS_NOT_DEFINED; + } + + can_bus_obtain(bus); + + bus->can_dev_ops->dev_ioctl(bus->priv, NULL, 0); + + can_bus_release(bus); + + return RTEMS_SUCCESSFUL; +} + +static const rtems_filesystem_file_handlers_r can_bus_handler = { + .open_h = can_bus_open, + .close_h = rtems_filesystem_default_close, + .read_h = can_bus_read, + .write_h = can_bus_write, + .ioctl_h = can_bus_ioctl, + .lseek_h = rtems_filesystem_default_lseek, + .fstat_h = IMFS_stat, + .ftruncate_h = rtems_filesystem_default_ftruncate, + .fsync_h = rtems_filesystem_default_fsync_or_fdatasync, + .fdatasync_h = rtems_filesystem_default_fsync_or_fdatasync, + .fcntl_h = rtems_filesystem_default_fcntl, + .kqfilter_h = rtems_filesystem_default_kqfilter, + .mmap_h = rtems_filesystem_default_mmap, + .poll_h = rtems_filesystem_default_poll, + .readv_h = rtems_filesystem_default_readv, + .writev_h = rtems_filesystem_default_writev +}; + +static void can_bus_node_destroy(IMFS_jnode_t *node) +{ + can_bus *bus; + + bus = IMFS_generic_get_context_by_node(node); + (*bus->destroy)(bus); + + IMFS_node_destroy_default(node); +} + +static const +IMFS_node_control can_bus_node_control = IMFS_GENERIC_INITIALIZER(&can_bus_handler, + IMFS_node_initialize_generic, can_bus_node_destroy); + +rtems_status_code can_bus_register(can_bus *bus, const char *bus_path) +{ + int ret = RTEMS_SUCCESSFUL; + + static uint8_t index = 0; + + if (index == 255) { + printf("can_bus_register: can bus registration limit reached\n"); + return RTEMS_TOO_MANY; + } + + bus->index = index++; + CAN_DEBUG("Registering CAN bus index = %u\n", bus->index); + + ret = IMFS_make_generic_node(bus_path, S_IFCHR | S_IRWXU | S_IRWXG | S_IRWXO, + &can_bus_node_control, bus); + if (ret != RTEMS_SUCCESSFUL) { + printf("can_bus_register: Creating node failed = %d\n", ret); + goto fail; + } + + if ((ret = can_create_sem(bus)) != RTEMS_SUCCESSFUL) { + printf("can_bus_register: can_create_sem failed = %d\n", ret); + goto fail; + } + + if ((ret = can_create_tx_buffers(bus)) != RTEMS_SUCCESSFUL) { + printf("can_bus_register: can_create_tx_buffers failed = %d\n", ret); + goto fail; + } + + if ((ret = can_create_rx_buffers(bus)) != RTEMS_SUCCESSFUL) { + printf("can_bus_register: can_create_rx_buffers failed = %d\n", ret); + goto free_tx_buffers_return; + } + + return ret; + +free_tx_buffers_return: + free(bus->tx_fifo.pbuf); + +fail: + (*bus->destroy)(bus); + return ret; + +} + +static void can_bus_destroy(can_bus *bus) +{ + rtems_recursive_mutex_destroy(&bus->mutex); +} + +static int can_bus_do_init(can_bus *bus, void (*destroy)(can_bus *bus)) +{ + rtems_recursive_mutex_init(&bus->mutex, "CAN Bus"); + bus->destroy = can_bus_destroy; + + return RTEMS_SUCCESSFUL; +} + +static void can_bus_destroy_and_free(can_bus *bus) +{ + can_bus_destroy(bus); + free(bus); +} + +int can_bus_init(can_bus *bus) +{ + memset(bus, 0, sizeof(*bus)); + + return can_bus_do_init(bus, can_bus_destroy); +} + +can_bus *can_bus_alloc_and_init(size_t size) +{ + can_bus *bus = NULL; + + if (size >= sizeof(*bus)) { + bus = calloc(1, size); + if (bus == NULL) { + printf("can_bus_alloc_and_init: calloc failed\b"); + return NULL; + } + + int rv = can_bus_do_init(bus, can_bus_destroy_and_free); + if (rv != 0) { + printf("can_bus_alloc_and_init: can_bus_do_init failed\n"); + return NULL; + } + } + return bus; +} diff --git a/cpukit/include/dev/can/can-msg.h b/cpukit/include/dev/can/can-msg.h new file mode 100644 index 0000000000..5c79b91600 --- /dev/null +++ b/cpukit/include/dev/can/can-msg.h @@ -0,0 +1,55 @@ +/* SPDX-License-Identifier: BSD-2-Clause */ + +/** + * @file + * + * @ingroup CANBus + * + * @brief Controller Area Network (CAN) Bus Implementation + * + */ + +/* + * Copyright (C) 2022 Prashanth S <fishesprasha...@gmail.com> + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef _DEV_CAN_CAN_MSG_H +#define _DEV_CAN_CAN_MSG_H + +#define CAN_MSG_MAX_SIZE (8u) + +#define CAN_TX_BUF_COUNT (2u) +#define CAN_RX_BUF_COUNT (2u) + +#define CAN_MSGLEN(msg) (sizeof(struct can_msg) - (CAN_MSG_MAX_SIZE - msg->len)) + +struct can_msg { + uint32_t id; // 32 bits to support extended id (29 bits). + uint32_t timestamp; + uint16_t flags; // RTR | BRS | EXT ... + uint16_t len; + uint8_t data[CAN_MSG_MAX_SIZE]; // For supporting data transfer up to 64 bytes. +}; + +#endif /* _DEV_CAN_CAN_MSG_H */ diff --git a/cpukit/include/dev/can/can-queue.h b/cpukit/include/dev/can/can-queue.h new file mode 100644 index 0000000000..c018441320 --- /dev/null +++ b/cpukit/include/dev/can/can-queue.h @@ -0,0 +1,127 @@ +/* SPDX-License-Identifier: BSD-2-Clause */ + +/** + * @file + * + * @ingroup CANBus + * + * @brief Controller Area Network (CAN) Bus Implementation + * + */ + +/* + * Copyright (C) 2022 Prashanth S <fishesprasha...@gmail.com> + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef _DEV_CAN_CAN_QUEUE_H +#define _DEV_CAN_CAN_QUEUE_H + +#include <rtems/imfs.h> +#include <rtems/thread.h> + +#include <string.h> +#include <stdlib.h> +#include <stdio.h> + +#include <dev/can/can-msg.h> +#include <dev/can/can.h> + +static rtems_status_code can_create_tx_buffers(struct can_bus *bus); +static rtems_status_code can_create_rx_buffers(struct can_bus *bus); +static bool can_tx_buf_isempty(struct can_bus *bus); +static struct can_msg *can_tx_get_data_buf(struct can_bus *bus); +static struct can_msg *can_tx_get_empty_buf(struct can_bus *bus); + +static rtems_status_code can_create_rx_buffers(struct can_bus *bus) +{ + return rtems_message_queue_create(rtems_build_name('c', 'a', 'n', bus->index), + CAN_RX_BUF_COUNT, sizeof(struct can_msg), + RTEMS_FIFO | RTEMS_LOCAL, &bus->rx_queue_id); +} + +static rtems_status_code can_create_tx_buffers(struct can_bus *bus) +{ + bus->tx_fifo.pbuf = (struct can_msg *)malloc(CAN_TX_BUF_COUNT * + sizeof(struct can_msg)); + if (bus->tx_fifo.pbuf == NULL) { + printf("can_create_tx_buffers: malloc failed\n"); + return RTEMS_NO_MEMORY; + } + + bus->tx_fifo.empty_count = CAN_TX_BUF_COUNT; + + return RTEMS_SUCCESSFUL; +} + +static bool can_tx_buf_isempty(struct can_bus *bus) +{ + if (bus->tx_fifo.empty_count == 0) { + return false; + } + + return true; +} + +// TODO: free the given data buf is done in the same function +// SO the returned buffer should be consumed before releasing the +// lock acquired while calling this function. +static struct can_msg *can_tx_get_data_buf(struct can_bus *bus) +{ + struct can_msg *msg = NULL; + + if (bus->tx_fifo.empty_count == CAN_TX_BUF_COUNT) { + CAN_DEBUG_BUF("can_tx_get_data_buf: All buffers are empty\n"); + return NULL; + } + + msg = &bus->tx_fifo.pbuf[bus->tx_fifo.tail]; + bus->tx_fifo.empty_count++; + bus->tx_fifo.tail = (bus->tx_fifo.tail + 1) % CAN_TX_BUF_COUNT; + + return msg; +} + +// TODO: marking the given buf as produced is done in the same function +// So the returned buffer should be produced before releasing the +// lock acquired while calling this function. +static struct can_msg *can_tx_get_empty_buf(struct can_bus *bus) +{ + struct can_msg *msg = NULL; + + /* Check whether there is a empty CAN msg buffer */ + if (can_tx_buf_isempty(bus) == false) { + CAN_DEBUG_BUF("can_tx_get_empty_buf: No empty buffer\n"); + return NULL; + } + + bus->tx_fifo.empty_count--; + + /* tx_fifo.head always points to a empty buffer if there is atleast one */ + msg = &bus->tx_fifo.pbuf[bus->tx_fifo.head]; + bus->tx_fifo.head = (bus->tx_fifo.head + 1) % CAN_TX_BUF_COUNT; + + return msg; +} + +#endif /*_DEV_CAN_CAN_QUEUE_H */ diff --git a/cpukit/include/dev/can/can.h b/cpukit/include/dev/can/can.h new file mode 100644 index 0000000000..eeb2eb2c0b --- /dev/null +++ b/cpukit/include/dev/can/can.h @@ -0,0 +1,102 @@ +/* SPDX-License-Identifier: BSD-2-Clause */ + +/** + * @file + * + * @ingroup CANBus + * + * @brief Controller Area Network (CAN) Bus Implementation + * + */ + +/* + * Copyright (C) 2022 Prashanth S (fishesprasha...@gmail.com) + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef _DEV_CAN_CAN_H +#define _DEV_CAN_CAN_H + +#include <rtems/imfs.h> +#include <rtems/thread.h> +#include <semaphore.h> + +#include <string.h> +#include <stdlib.h> +#include <stdio.h> + +#include <dev/can/can-msg.h> + +#define CAN_DEBUG(str, ...) printf(str, ##__VA_ARGS__) +#define CAN_DEBUG_BUF(str, ...) printf(str, ##__VA_ARGS__) +#define CAN_DEBUG_ISR(str, ...) printf(str, ##__VA_ARGS__) +#define CAN_DEBUG_LOCK(str, ...) printf(str, ##__VA_ARGS__) +#define CAN_DEBUG_RX(str, ...) printf(str, ##__VA_ARGS__) +#define CAN_DEBUG_TX(str, ...) printf(str, ##__VA_ARGS__) + +struct ring_buf { + struct can_msg *pbuf; + uint32_t head; + uint32_t tail; + uint32_t empty_count; +}; + +typedef struct can_dev_ops { + int32_t (*dev_rx)(void *priv, void *buffer); + int32_t (*dev_tx)(void *priv, void *buffer); + bool (*dev_tx_ready)(void *priv); + void (*dev_int)(void *priv, bool); + int32_t (*dev_ioctl)(void *priv, void *buffer, size_t cmd); +} can_dev_ops; + +typedef struct can_bus { + void *priv; // CAN controller specific struct. + uint8_t index; + struct can_dev_ops *can_dev_ops; // CAN controller operations. + + struct ring_buf tx_fifo; // TX fifo + rtems_id tx_fifo_sem_id; // TX fifo counting semaphore id + uint32_t can_tx_buf_waiters; + + rtems_id rx_queue_id; + uint32_t rx_queue_name; + + rtems_recursive_mutex mutex; // For handling driver concurrency. + RTEMS_INTERRUPT_LOCK_MEMBER(can_bus_lock); + + void (*destroy)(struct can_bus *bus); // Clean the CAN controller specific resources. +} can_bus; + +extern rtems_status_code can_bus_register(can_bus *bus, const char *bus_path); + +extern can_bus *can_bus_alloc_and_init(size_t size); +extern int can_bus_init(can_bus *bus); +extern int can_tx_done(struct can_bus *); +extern int can_receive(struct can_bus *, struct can_msg *); + +extern uint16_t can_len_to_dlc(uint16_t len); +extern uint16_t can_dlc_to_len(uint16_t dlc); + +extern void can_print_msg(struct can_msg const *); + +#endif /* _DEV_CAN_CAN_H */ diff --git a/spec/build/cpukit/librtemscpu.yml b/spec/build/cpukit/librtemscpu.yml index 31a68cf85a..b7f6c0457c 100644 --- a/spec/build/cpukit/librtemscpu.yml +++ b/spec/build/cpukit/librtemscpu.yml @@ -50,6 +50,11 @@ install: - destination: ${BSP_INCLUDEDIR}/dev/spi source: - cpukit/include/dev/spi/spi.h +- destination: ${BSP_INCLUDEDIR}/dev/can + source: + - cpukit/include/dev/can/can.h + - cpukit/include/dev/can/can-msg.h + - cpukit/include/dev/can/can-queue.h - destination: ${BSP_INCLUDEDIR}/linux source: - cpukit/include/linux/i2c-dev.h @@ -530,6 +535,7 @@ source: - cpukit/dev/serial/sc16is752-spi.c - cpukit/dev/serial/sc16is752.c - cpukit/dev/spi/spi-bus.c +- cpukit/dev/can/can.c - cpukit/dtc/libfdt/fdt.c - cpukit/dtc/libfdt/fdt_addresses.c - cpukit/dtc/libfdt/fdt_empty_tree.c -- 2.25.1 _______________________________________________ devel mailing list devel@rtems.org http://lists.rtems.org/mailman/listinfo/devel