devel Digest, Vol 129, Issue 37
Prashanth S
fishesprashanth at gmail.com
Sun Aug 21 06:02:30 UTC 2022
Hi All,
This is a review request for DCAN and CAN support. The review comments
would be very helpful for stabilizing the source files.
https://gitlab.com/slpp95prashanth/gsoc-2022/-/tree/can-review-latest-squash-02-squash/
Regards
Prashanth S
On Mon, 15 Aug 2022 at 11:57, Prashanth S <fishesprashanth at gmail.com> wrote:
>
> Hi All,
>
> This is a review request for DCAN (Work in Progress) support.
>
> As the patch size exceeds the mail limit, I am attaching the patch in
> compressed format.
>
> Regards
> Prashanth S
>
> Prashanth S
>
> On Sun, 14 Aug 2022 at 13:56, <devel-request at rtems.org> wrote:
> >
> > Send devel mailing list submissions to
> > devel at rtems.org
> >
> > To subscribe or unsubscribe via the World Wide Web, visit
> > http://lists.rtems.org/mailman/listinfo/devel
> > or, via email, send a message with subject or body 'help' to
> > devel-request at rtems.org
> >
> > You can reach the person managing the list at
> > devel-owner at rtems.org
> >
> > When replying, please edit your Subject line so it is more specific
> > than "Re: Contents of devel digest..."
> >
> >
> > Today's Topics:
> >
> > 1. [PATCH v4] cpukit/dev/can: Added CAN support (Prashanth S)
> >
> >
> > ----------------------------------------------------------------------
> >
> > Message: 1
> > Date: Sun, 14 Aug 2022 13:56:16 +0530
> > From: Prashanth S <fishesprashanth at gmail.com>
> > To: devel at rtems.org
> > Cc: Prashanth S <fishesprashanth at gmail.com>
> > Subject: [PATCH v4] cpukit/dev/can: Added CAN support
> > Message-ID: <20220814082616.7345-1-fishesprashanth at gmail.com>
> >
> > ---
> > cpukit/dev/can/can.c | 521 +++++++++++++++++++++++
> > cpukit/include/dev/can/can-msg.h | 105 +++++
> > cpukit/include/dev/can/can-queue.h | 219 ++++++++++
> > cpukit/include/dev/can/can.h | 258 +++++++++++
> > spec/build/cpukit/librtemscpu.yml | 6 +
> > spec/build/testsuites/libtests/can01.yml | 19 +
> > spec/build/testsuites/libtests/grp.yml | 2 +
> > testsuites/libtests/can01/init.c | 257 +++++++++++
> > 8 files changed, 1387 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
> > create mode 100644 spec/build/testsuites/libtests/can01.yml
> > create mode 100644 testsuites/libtests/can01/init.c
> >
> > diff --git a/cpukit/dev/can/can.c b/cpukit/dev/can/can.c
> > new file mode 100644
> > index 0000000000..02377a9098
> > --- /dev/null
> > +++ b/cpukit/dev/can/can.c
> > @@ -0,0 +1,521 @@
> > +/* SPDX-License-Identifier: BSD-2-Clause */
> > +
> > +/**
> > + * @file
> > + *
> > + * @ingroup CANBus
> > + *
> > + * @brief Controller Area Network (CAN) Bus Implementation
> > + *
> > + */
> > +
> > +/*
> > + * Copyright (C) 2022 Prashanth S (fishesprashanth at 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>
> > +
> > +#define can_interrupt_lock_acquire(bus) \
> > + do { \
> > + CAN_DEBUG_LOCK("acquiring lock %s:%d\n", __FILE__, __LINE__); \
> > + real_can_interrupt_lock_acquire(bus); \
> > + } while (0);
> > +
> > +#define can_interrupt_lock_release(bus) \
> > + do { \
> > + CAN_DEBUG_LOCK("releasing lock %s:%d\n", __FILE__, __LINE__); \
> > + real_can_interrupt_lock_release(bus); \
> > + } while (0);
> > +
> > +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)
> > +{
> > + printf("can_bus_obtain Entry\n");
> > + rtems_mutex_lock(&bus->mutex);
> > + printf("can_bus_obtain Exit\n");
> > +}
> > +
> > +static void can_bus_release(can_bus *bus)
> > +{
> > + printf("can_bus_release Entry\n");
> > + rtems_mutex_unlock(&bus->mutex);
> > + printf("can_bus_release Exit\n");
> > +}
> > +
> > +static void can_bus_destroy_mutex(struct can_bus *bus)
> > +{
> > + rtems_mutex_destroy(&bus->mutex);
> > +}
> > +
> > +static 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_free_tx_semaphore(struct can_bus *bus)
> > +{
> > + rtems_semaphore_delete(bus->tx_fifo_sem_id);
> > +}
> > +
> > +static void real_can_interrupt_lock_acquire(struct can_bus *bus)
> > +{
> > + bus->can_dev_ops->dev_int(bus->priv, false);
> > + can_bus_obtain(bus);
> > +}
> > +
> > +static void real_can_interrupt_lock_release(struct can_bus *bus)
> > +{
> > + can_bus_release(bus);
> > + bus->can_dev_ops->dev_int(bus->priv, true);
> > +}
> > +
> > +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) {
> > + sem_count++;
> > + CAN_DEBUG_LOCK("take_sem: 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) {
> > + sem_count--;
> > + CAN_DEBUG_LOCK("give_sem: 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) {
> > + sem_count++;
> > + CAN_DEBUG_LOCK("try_sem: 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_DEBUG("can_bus_open\n");
> > +/*
> > + 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) {
> > + 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;
> > +}
> > +
> > +/* This function is a critical section and should be called
> > + * with CAN interrupts disabled and mutual exclusive
> > + */
> > +static int can_xmit(struct can_bus *bus)
> > +{
> > + int ret = RTEMS_SUCCESSFUL;
> > +
> > + struct can_msg *msg = NULL;
> > +
> > + CAN_DEBUG(">>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>> can_xmit Entry\n");
> > +
> > + while (1) {
> > + printf("can_dev_ops->dev_tx_ready\n");
> > + ret = bus->can_dev_ops->dev_tx_ready(bus->priv);
> > + if (ret != true) {
> > + break;
> > + }
> > + printf("can_tx_get_data_buf\n");
> > + msg = can_tx_get_data_buf(bus);
> > + if (msg == NULL) {
> > + break;
> > + }
> > + printf("can_dev_ops->dev_tx\n");
> > + 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(">>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>> can_xmit Exit\n");
> > +
> > + 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)
> > +{
> > + CAN_DEBUG("------------ can_tx_done Entry\n");
> > + int ret = 0;
> > +
> > + if (bus->can_dev_ops->dev_tx_ready(bus->priv) == true) {
> > + can_xmit(bus);
> > + }
> > + CAN_DEBUG("------------ can_tx_done Exit\n");
> > +
> > + 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;
> > +
> > + if ((iop->flags & O_NONBLOCK) != 0) {
> > + ret = try_sem(bus);
> > + if (ret != RTEMS_SUCCESSFUL) {
> > + return -ret;
> > + }
> > + } else {
> > + ret = take_sem(bus);
> > + if (ret != RTEMS_SUCCESSFUL) {
> > + printf("can_bus_write: cannot take semaphore\n");
> > + return -ret;
> > + }
> > + }
> > +
> > + /* 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_interrupt_lock_acquire(bus);
> > +
> > + fifo_buf = can_tx_get_empty_buf(bus);
> > + if (fifo_buf == NULL) {
> > + printf("can_bus_write: Buffer counts are not synchronized with semaphore count\n");
> > + return -RTEMS_INTERNAL_ERROR;
> > + }
> > +
> > + CAN_DEBUG_TX("can_bus_write: empty_count = %u\n", bus->tx_fifo.empty_count);
> > +
> > + /* 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);
> > + }
> > + can_interrupt_lock_release(bus);
> > +
> > + 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 free_tx_semaphore;
> > + }
> > +
> > + 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 ret;
> > +
> > +free_tx_buffers:
> > + free(bus->tx_fifo.pbuf);
> > +
> > +free_tx_semaphore:
> > + rtems_semaphore_delete(bus->tx_fifo_sem_id);
> > +
> > +fail:
> > + can_bus_destroy_mutex(bus);
> > + return ret;
> > +
> > +}
> > +
> > +static void can_bus_destroy(can_bus *bus)
> > +{
> > + can_free_rx_buffers(bus);
> > + can_free_tx_buffers(bus);
> > + can_free_tx_semaphore(bus);
> > + can_bus_destroy_mutex(bus);
> > +}
> > +
> > +static int can_bus_do_init(can_bus *bus, void (*destroy)(can_bus *bus))
> > +{
> > + rtems_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..9863e14d84
> > --- /dev/null
> > +++ b/cpukit/include/dev/can/can-msg.h
> > @@ -0,0 +1,105 @@
> > +/* SPDX-License-Identifier: BSD-2-Clause */
> > +
> > +/**
> > + * @file
> > + *
> > + * @ingroup CANBus
> > + *
> > + * @brief Controller Area Network (CAN) Bus Implementation
> > + *
> > + */
> > +
> > +/*
> > + * Copyright (C) 2022 Prashanth S <fishesprashanth at 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
> > +
> > +/**
> > + * @defgroup Controller Area Network (CAN) Driver
> > + *
> > + * @ingroup RTEMSDeviceDrivers
> > + *
> > + * @brief Controller Area Network (CAN) bus and device driver support.
> > + *
> > + * @{
> > + */
> > +
> > +/**
> > + * @defgroup CANBus CAN Bus Driver
> > + *
> > + * @ingroup CAN
> > + *
> > + * @{
> > + */
> > +
> > +/**
> > + * @brief CAN message size
> > + */
> > +#define CAN_MSG_MAX_SIZE (8u)
> > +
> > +/**
> > + * @brief Number of CAN tx buffers
> > + */
> > +#define CAN_TX_BUF_COUNT (10u)
> > +
> > +/**
> > + * @brief Number of CAN rx buffers
> > + */
> > +#define CAN_RX_BUF_COUNT (2u)
> > +
> > +#define CAN_MSGLEN(msg) (sizeof(struct can_msg) - (CAN_MSG_MAX_SIZE - msg->len))
> > +
> > +/**
> > + * @brief CAN message structure.
> > + */
> > +struct can_msg {
> > + /**
> > + * @brief CAN message id.
> > + */
> > + uint32_t id;
> > + /**
> > + * @brief CAN message timestamp.
> > + */
> > + uint32_t timestamp;
> > + /**
> > + * @brief CAN message flags RTR | BRS | EXT.
> > + */
> > + uint16_t flags;
> > + /**
> > + * @brief CAN message length.
> > + */
> > + uint16_t len;
> > + /**
> > + * @brief CAN message.
> > + */
> > + uint8_t data[CAN_MSG_MAX_SIZE];
> > +};
> > +
> > +/** @} */ /* end of CAN message */
> > +
> > +/** @} */
> > +
> > +#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..0d8aa78a84
> > --- /dev/null
> > +++ b/cpukit/include/dev/can/can-queue.h
> > @@ -0,0 +1,219 @@
> > +/* SPDX-License-Identifier: BSD-2-Clause */
> > +
> > +/**
> > + * @file
> > + *
> > + * @ingroup CANBus
> > + *
> > + * @brief Controller Area Network (CAN) Bus Implementation
> > + *
> > + */
> > +
> > +/*
> > + * Copyright (C) 2022 Prashanth S <fishesprashanth at 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>
> > +
> > +/**
> > + * @defgroup Controller Area Network (CAN) Driver
> > + *
> > + * @ingroup RTEMSDeviceDrivers
> > + *
> > + * @brief Controller Area Network (CAN) bus and device driver support.
> > + *
> > + * @{
> > + */
> > +
> > +/**
> > + * @defgroup CANBus CAN Bus Driver
> > + *
> > + * @ingroup CAN
> > + *
> > + * @{
> > + */
> > +
> > +/**
> > + * @brief Create CAN tx buffers.
> > + *
> > + * @param[in] bus Bus control structure.
> > + *
> > + * @retval 0 Successful operation.
> > + * @retval >0 error number in case of an error.
> > + */
> > +static rtems_status_code can_create_tx_buffers(struct can_bus *bus);
> > +
> > +/**
> > + * @brief Create CAN rx buffers.
> > + *
> > + * @param[in] bus Bus control structure.
> > + *
> > + * @retval 0 Successful operation.
> > + * @retval >0 error number in case of an error.
> > + */
> > +static rtems_status_code can_create_rx_buffers(struct can_bus *bus);
> > +
> > +/**
> > + * @brief Free CAN tx buffers.
> > + *
> > + * @param[in] bus Bus control structure.
> > + *
> > + */
> > +static void can_free_tx_buffers(struct can_bus *bus);
> > +
> > +/**
> > + * @brief Free CAN rx buffers.
> > + *
> > + * @param[in] bus Bus control structure.
> > + *
> > + */
> > +static void can_free_rx_buffers(struct can_bus *bus);
> > +
> > +/**
> > + * @brief Check for atleast one empty CAN tx buffer.
> > + *
> > + * @param[in] bus Bus control structure.
> > + *
> > + * @retval true If atleast one CAN buffer is empty.
> > + * @retval false If no CAN buffer is empty.
> > + */
> > +static bool can_tx_buf_isempty(struct can_bus *bus);
> > +
> > +/**
> > + * @brief Get a produced tx buffer to process.
> > + *
> > + * @param[in] bus Bus control structure.
> > + *
> > + * @retval can_msg Pointer to can_msg structure buffer.
> > + * @retval NULL If no can_msg buffer.
> > + */
> > +static struct can_msg *can_tx_get_data_buf(struct can_bus *bus);
> > +
> > +/**
> > + * @brief Get a empty tx buffer.
> > + *
> > + * @param[in] bus Bus control structure.
> > + *
> > + * @retval can_msg Pointer to can_msg structure buffer.
> > + * @retval NULL If no empty can_msg buffer.
> > + */
> > +static struct can_msg *can_tx_get_empty_buf(struct can_bus *bus);
> > +
> > +/** @} */ /* end of i2c device driver */
> > +
> > +/** @} */
> > +
> > +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 void can_free_tx_buffers(struct can_bus *bus)
> > +{
> > + free(bus->tx_fifo.pbuf);
> > +}
> > +
> > +static void can_free_rx_buffers(struct can_bus *bus)
> > +{
> > + rtems_message_queue_delete(bus->rx_queue_id);
> > +}
> > +
> > +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..0074a3dd8f
> > --- /dev/null
> > +++ b/cpukit/include/dev/can/can.h
> > @@ -0,0 +1,258 @@
> > +/* SPDX-License-Identifier: BSD-2-Clause */
> > +
> > +/**
> > + * @file
> > + *
> > + * @ingroup CANBus
> > + *
> > + * @brief Controller Area Network (CAN) Bus Implementation
> > + *
> > + */
> > +
> > +/*
> > + * Copyright (C) 2022 Prashanth S (fishesprashanth at 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("CAN: %s:%d ID: %08X ", __FILE__, __LINE__, rtems_task_self());printf(str, ##__VA_ARGS__)
> > +#define CAN_DEBUG_BUF(str, ...) printf("CAN: %s:%d ID: %08X ", __FILE__, __LINE__, rtems_task_self());printf(str, ##__VA_ARGS__)
> > +#define CAN_DEBUG_ISR(str, ...) printf("CAN: %s:%d ID: %08X ", __FILE__, __LINE__, rtems_task_self());printf(str, ##__VA_ARGS__)
> > +#define CAN_DEBUG_LOCK(str, ...) printf("CAN: %s:%d ID: %08X ", __FILE__, __LINE__, rtems_task_self());printf(str, ##__VA_ARGS__)
> > +#define CAN_DEBUG_RX(str, ...) printf("CAN: %s:%d ID: %08X ", __FILE__, __LINE__, rtems_task_self());printf(str, ##__VA_ARGS__)
> > +#define CAN_DEBUG_TX(str, ...) printf("CAN: %s:%d ID: %08X ", __FILE__, __LINE__, rtems_task_self());printf(str, ##__VA_ARGS__)
> > +
> > +/**
> > + * @defgroup Controller Area Network (CAN) Driver
> > + *
> > + * @ingroup RTEMSDeviceDrivers
> > + *
> > + * @brief Controller Area Network (CAN) bus and device driver support.
> > + *
> > + * @{
> > + */
> > +
> > +/**
> > + * @defgroup CANBus CAN Bus Driver
> > + *
> > + * @ingroup CAN
> > + *
> > + * @{
> > + */
> > +
> > +/**
> > + * @brief CAN tx fifo data structure.
> > + */
> > +struct ring_buf {
> > + /**
> > + * @brief Pointer to array of can_msg structure.
> > + */
> > + struct can_msg *pbuf;
> > + /**
> > + * @brief Index of the next free buffer.
> > + */
> > + uint32_t head;
> > + /**
> > + * @brief Index of the produced buffer.
> > + */
> > + uint32_t tail;
> > + /**
> > + * @brief Number of empty buffers.
> > + */
> > + uint32_t empty_count;
> > +};
> > +
> > +/**
> > + * @brief CAN device specific operations.
> > + */
> > +typedef struct can_dev_ops {
> > + /**
> > + * @brief Transfers CAN messages to device fifo.
> > + *
> > + * @param[in] priv device control structure.
> > + * @param[in] msg can_msg message structure.
> > + *
> > + * @retval 0 Successful operation.
> > + * @retval >0 error number in case of an error.
> > + */
> > + int32_t (*dev_tx)(void *priv, struct can_msg *msg);
> > + /**
> > + * @brief Check device is ready to transfer a CAN message
> > + *
> > + * @param[in] priv device control structure.
> > + *
> > + * @retval true device ready.
> > + * @retval false device not ready.
> > + */
> > + bool (*dev_tx_ready)(void *priv);
> > + /**
> > + * @brief Enable/Disable CAN interrupts.
> > + *
> > + * @param[in] priv device control structure.
> > + * @param[in] flag true/false to Enable/Disable CAN interrupts.
> > + *
> > + */
> > + void (*dev_int)(void *priv, bool flag);
> > + /**
> > + * @brief CAN device specific I/O controls.
> > + *
> > + * @param[in] priv device control structure.
> > + * @param[in] buffer This depends on the cmd.
> > + * @param[in] cmd Device specific I/O commands.
> > + *
> > + * @retval 0 Depends on the cmd.
> > + */
> > + int32_t (*dev_ioctl)(void *priv, void *buffer, size_t cmd);
> > +} can_dev_ops;
> > +
> > +/**
> > + * @name CAN bus control
> > + *
> > + * @{
> > + */
> > +
> > +/**
> > + * @brief Obtains the bus.
> > + *
> > + * This command has no argument.
> > + */
> > +typedef struct can_bus {
> > + /**
> > + * @brief Device specific control.
> > + */
> > + void *priv;
> > + /**
> > + * @brief Device controller index.
> > + */
> > + uint8_t index;
> > + /**
> > + * @brief Device specific operations.
> > + */
> > + struct can_dev_ops *can_dev_ops;
> > + /**
> > + * @brief tx fifo.
> > + */
> > + struct ring_buf tx_fifo;
> > + /**
> > + * @brief Counting semaphore id (for fifo sync).
> > + */
> > + rtems_id tx_fifo_sem_id;
> > + /**
> > + * @brief rx message queue id.
> > + */
> > + rtems_id rx_queue_id;
> > + /**
> > + * @brief rx message queue name.
> > + */
> > + uint32_t rx_queue_name;
> > + /**
> > + * @brief Mutex to handle bus concurrency.
> > + */
> > + rtems_mutex mutex; // For handling driver concurrency.
> > + /**
> > + * @brief Destroys the bus.
> > + *
> > + * @param[in] bus control structure.
> > + */
> > + void (*destroy)(struct can_bus *bus); // Clean the CAN controller specific resources.
> > +} can_bus;
> > +
> > +/** @} */
> > +
> > +/**
> > + * @brief Register a CAN node with the CAN bus driver.
> > + *
> > + * @param[in] bus bus control structure.
> > + * @param[in] bus_path path of device node.
> > + *
> > + * @retval >=0 rtems status.
> > + */
> > +extern rtems_status_code can_bus_register(can_bus *bus, const char *bus_path);
> > +
> > +/**
> > + * @brief Allocate and initilaize bus control structure.
> > + *
> > + * @param[in] size Size of the bus control structure.
> > + *
> > + * @retval NULL No memory available.
> > + * @retval Address Pointer to the allocated bus control structure.
> > + */
> > +extern can_bus *can_bus_alloc_and_init(size_t size);
> > +
> > +/**
> > + * @brief initilaize bus control structure.
> > + *
> > + * @param[in] bus bus control structure.
> > + *
> > + * @retval 0 success.
> > + * @retval >0 error number.
> > + */
> > +extern int can_bus_init(can_bus *bus);
> > +
> > +/**
> > + * @brief Initiates CAN message transfer.
> > + *
> > + * Should be called in interrupt context.
> > + *
> > + * @param[in] bus bus control structure.
> > + *
> > + * @retval 0 success.
> > + * @retval >0 error number.
> > + */
> > +extern int can_tx_done(struct can_bus *bus);
> > +
> > +/**
> > + * @brief Sends the received CAN message to the application.
> > + *
> > + * Should be called by the device when CAN message should be sent to applicaiton.
> > + *
> > + * @param[in] bus bus control structure.
> > + * @param[in] msg can_msg structure.
> > + *
> > + * @retval 0 success.
> > + * @retval >0 error number.
> > + */
> > +extern int can_receive(struct can_bus *bus, struct can_msg *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 *);
> > +
> > +/** @} */ /* end of CAN device driver */
> > +
> > +/** @} */
> > +
> > +#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
> > diff --git a/spec/build/testsuites/libtests/can01.yml b/spec/build/testsuites/libtests/can01.yml
> > new file mode 100644
> > index 0000000000..2d5be51db1
> > --- /dev/null
> > +++ b/spec/build/testsuites/libtests/can01.yml
> > @@ -0,0 +1,19 @@
> > +SPDX-License-Identifier: CC-BY-SA-4.0 OR BSD-2-Clause
> > +build-type: test-program
> > +cflags: []
> > +copyrights:
> > +- Copyright (C) 2020 embedded brains GmbH (http://www.embedded-brains.de)
> > +cppflags: []
> > +cxxflags: []
> > +enabled-by: true
> > +features: c cprogram
> > +includes: []
> > +ldflags: []
> > +links: []
> > +source:
> > +- testsuites/libtests/can01/init.c
> > +stlib: []
> > +target: testsuites/libtests/can01.exe
> > +type: build
> > +use-after: []
> > +use-before: []
> > diff --git a/spec/build/testsuites/libtests/grp.yml b/spec/build/testsuites/libtests/grp.yml
> > index 2aa7fa058e..9d91df75a0 100644
> > --- a/spec/build/testsuites/libtests/grp.yml
> > +++ b/spec/build/testsuites/libtests/grp.yml
> > @@ -76,6 +76,8 @@ links:
> > uid: cpuuse
> > - role: build-dependency
> > uid: crypt01
> > +- role: build-dependency
> > + uid: can01
> > - role: build-dependency
> > uid: debugger01
> > - role: build-dependency
> > diff --git a/testsuites/libtests/can01/init.c b/testsuites/libtests/can01/init.c
> > new file mode 100644
> > index 0000000000..2fc7e2fe8a
> > --- /dev/null
> > +++ b/testsuites/libtests/can01/init.c
> > @@ -0,0 +1,257 @@
> > +/*
> > + * COPYRIGHT (c) 1989-2012.
> > + * On-Line Applications Research Corporation (OAR).
> > + *
> > + * The license and distribution terms for this file may be
> > + * found in the file LICENSE in this distribution or at
> > + * http://www.rtems.org/license/LICENSE.
> > + */
> > +
> > +#ifdef HAVE_CONFIG_H
> > +#include "config.h"
> > +#endif
> > +
> > +#include <rtems.h>
> > +#include <tmacros.h>
> > +#include <unistd.h>
> > +#include <stdlib.h>
> > +#include <errno.h>
> > +#include <fcntl.h>
> > +#include <inttypes.h>
> > +#include <rtems/error.h>
> > +
> > +#include <dev/can/can.h>
> > +
> > +#define TASKS 12
> > +
> > +#include <sys/time.h>
> > +#include <errno.h>
> > +#include <inttypes.h>
> > +#include <sched.h>
> > +#include <stdint.h>
> > +#include <unistd.h>
> > +
> > +#include <pthread.h>
> > +
> > +#define NEXT_TASK_NAME(c1, c2, c3, c4) \
> > + if (c4 == '9') { \
> > + if (c3 == '9') { \
> > + if (c2 == 'z') { \
> > + if (c1 == 'z') { \
> > + printf("not enough task letters for names !!!\n"); \
> > + exit( 1 ); \
> > + } else \
> > + c1++; \
> > + c2 = 'a'; \
> > + } else \
> > + c2++; \
> > + c3 = '0'; \
> > + } else \
> > + c3++; \
> > + c4 = '0'; \
> > + } \
> > + else \
> > + c4++ \
> > +
> > +
> > +const char rtems_test_name[] = "CAN test TX, RX with " "TASKS " "threads";
> > +
> > +void test_task_0(rtems_task_argument);
> > +bool status_code_bad(rtems_status_code);
> > +int create_task(int);
> > +
> > +void test_task_0(rtems_task_argument data)
> > +{
> > + sleep(1);
> > +
> > + uint32_t count = 0, fd = 0;
> > +
> > + struct can_msg msg;
> > +
> > + char str[12];
> > +
> > + snprintf(str, 12, "/dev/can%d", 1);
> > +
> > + printf(">>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>> CAN tx and rx for %s\n", str);
> > +
> > + fd = open(str, O_RDWR);
> > + rtems_test_assert(fd >= 0);
> > +
> > + if (fd < 0) {
> > + printf("open error %s: %s\n", str, strerror(errno));
> > + return;
> > + }
> > +
> > + for (int i = 0; i < 0xffff; i++) {
> > + printf(">>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>> test_task_0 %d\n", (int)data);
> > +
> > + msg.id = (uint32_t)data;
> > + msg.flags = 0;
> > + msg.len = (i + 1) % 9;
> > +
> > + msg.data[0] = '0';
> > + msg.data[1] = '1';
> > + msg.data[2] = 't';
> > + msg.data[3] = 'a';
> > + msg.data[4] = '-';
> > + msg.data[5] = '0';
> > +
> > + printf("calling write task = %d\n", (int)data);
> > + count = write(fd, &msg, sizeof(msg));
> > +
> > + printf(">>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>> task = %d\n", (int)data);
> > +
> > + printf("task = %d write count = %u\n", (int)data, count);
> > +
> > + printf("calling read task = %d\n", (int)data);
> > + count = read(fd, &msg, sizeof(msg));
> > + printf("task = %d read count = %u\n", (int)data, count);
> > +
> > + printf("++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ received message\n");
> > + can_print_msg(&msg);
> > + printf("++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ received message\n");
> > + }
> > +
> > + close(fd);
> > +}
> > +
> > +bool status_code_bad(
> > + rtems_status_code status_code
> > +)
> > +{
> > + if (status_code != RTEMS_SUCCESSFUL)
> > + {
> > + printf("failure, ");
> > +
> > + if (status_code == RTEMS_TOO_MANY)
> > + {
> > + printf("too many.\n");
> > + return TRUE;
> > + }
> > + if (status_code == RTEMS_UNSATISFIED)
> > + {
> > + printf("unsatisfied.\n");
> > + return TRUE;
> > + }
> > +
> > + printf("error code = %i\n", status_code);
> > + exit( 1 );
> > + }
> > + return FALSE;
> > +}
> > +
> > +int create_task(int i)
> > +{
> > + printf("Creating task %d\n", i);
> > +
> > +#ifndef _POSIX_THREADS_
> > +
> > + static rtems_id task_id[TASKS];
> > +
> > + rtems_status_code result;
> > + rtems_name name;
> > +
> > + char c1 = 'a';
> > + char c2 = 'a';
> > + char c3 = '1';
> > + char c4 = '1';
> > +
> > + name = rtems_build_name(c1, c2, c3, c4);
> > +
> > + result = rtems_task_create(name,
> > + 10,
> > + 1024 * 12,
> > + RTEMS_PREEMPT | RTEMS_TIMESLICE,
> > + RTEMS_FIFO,
> > + &task_id[i]);
> > + if (result != 0) {
> > + printf("rtems_task_create %d\n", result);
> > + return result;
> > + }
> > +
> > + printf("number = %3" PRIi32 ", id = %08" PRIxrtems_id ", starting, ", i, task_id[i]);
> > +
> > + fflush(stdout);
> > +
> > + result = rtems_task_start(task_id[i],
> > + test_task_0,
> > + (rtems_task_argument)i);
> > +
> > + if (status_code_bad(result)) {
> > + printf("rtems_task_start failed\n");
> > + return result;
> > + }
> > +
> > + NEXT_TASK_NAME(c1, c2, c3, c4);
> > +
> > +#else
> > +
> > + static pthread_t Task_id[TASKS];
> > +
> > + int status = pthread_create( &Task_id[i], NULL, test_task_0, (void *)i);
> > +
> > + if (status != 0) {
> > + printf("pthread_create failed %d\n", status);
> > + return status;
> > + }
> > + printf("Creating tasks\n");
> > +#endif /* _POSIX_THREADS_ */
> > + return 0;
> > +}
> > +
> > +static rtems_task Init(
> > + rtems_task_argument ignored
> > +)
> > +{
> > + printf("Init\n");
> > +
> > + rtems_print_printer_fprintf_putc(&rtems_test_printer);
> > +
> > + TEST_BEGIN();
> > +
> > + rtems_task_priority old_priority;
> > + rtems_mode old_mode;
> > +
> > + rtems_task_set_priority(RTEMS_SELF, RTEMS_MAXIMUM_PRIORITY - 1, &old_priority);
> > + rtems_task_mode(RTEMS_PREEMPT, RTEMS_PREEMPT_MASK, &old_mode);
> > +
> > + for (int i = 0; i < TASKS; i++) {
> > + create_task(i);
> > + }
> > +
> > + while(1);
> > +
> > + TEST_END();
> > +
> > + rtems_test_exit( 0 );
> > +}
> > +
> > +
> > +#define CONFIGURE_MICROSECONDS_PER_TICK 2000
> > +
> > +#define CONFIGURE_APPLICATION_NEEDS_CLOCK_DRIVER
> > +#define CONFIGURE_APPLICATION_NEEDS_SIMPLE_CONSOLE_DRIVER
> > +
> > +#define CONFIGURE_MAXIMUM_FILE_DESCRIPTORS 20
> > +
> > +#define CONFIGURE_MAXIMUM_TASKS 20
> > +
> > +#define CONFIGURE_MAXIMUM_SEMAPHORES 10
> > +
> > +#define CONFIGURE_MAXIMUM_MESSAGE_QUEUES 20
> > +//#define CONFIGURE_MESSAGE_BUFFER_MEMORY CONFIGURE_MESSAGE_BUFFERS_FOR_QUEUE(1, 1)
> > +
> > +#define CONFIGURE_INITIAL_EXTENSIONS RTEMS_TEST_INITIAL_EXTENSION
> > +
> > +#define CONFIGURE_RTEMS_INIT_TASKS_TABLE
> > +
> > +#define CONFIGURE_INIT
> > +
> > +#define CONFIGURE_MAXIMUM_POSIX_THREADS TASKS
> > +
> > +//#define CONFIGURE_POSIX_INIT_THREAD_TABLE
> > +
> > +//#define CONFIGURE_POSIX_INIT_THREAD_ENTRY_POINT POSIX_Init
> > +//#define CONFIGURE_POSIX_INIT_THREAD_ENTRY_POINT POSIX_Init
> > +
> > +#include <rtems/confdefs.h>
> > --
> > 2.25.1
> >
> >
> >
> > ------------------------------
> >
> > Subject: Digest Footer
> >
> > _______________________________________________
> > devel mailing list
> > devel at rtems.org
> > http://lists.rtems.org/mailman/listinfo/devel
> >
> > ------------------------------
> >
> > End of devel Digest, Vol 129, Issue 37
> > **************************************
More information about the devel
mailing list