[PATCH] cpukit/dev/can: Added CAN support

Prashanth S fishesprashanth at gmail.com
Fri Jul 15 18:11:32 UTC 2022


---
 cpukit/dev/can/can-queue.c        | 112 +++++++
 cpukit/dev/can/can.c              | 480 ++++++++++++++++++++++++++++++
 cpukit/include/dev/can/can.h      | 115 +++++++
 spec/build/cpukit/librtemscpu.yml |   5 +
 4 files changed, 712 insertions(+)
 create mode 100644 cpukit/dev/can/can-queue.c
 create mode 100644 cpukit/dev/can/can.c
 create mode 100644 cpukit/include/dev/can/can.h

diff --git a/cpukit/dev/can/can-queue.c b/cpukit/dev/can/can-queue.c
new file mode 100644
index 0000000000..1cebed2ca4
--- /dev/null
+++ b/cpukit/dev/can/can-queue.c
@@ -0,0 +1,112 @@
+/* SPDX-License-Identifier: BSD-2-Clause */
+
+/**
+ * @file
+ *
+ * @ingroup CANBus
+ *
+ * @brief Controller Area Network (CAN) Bus Implementation
+ *
+ */
+
+/*
+ * Copyright (C) 2022
+ *
+ * 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.h>
+
+#include <string.h>
+#include <stdlib.h>
+#include <stdio.h>
+
+rtems_status_code can_create_rx_buffers(struct can_bus *bus)
+{
+  static int init = 0;
+
+  return rtems_message_queue_create(rtems_build_name('c', 'a', 'n', '0' + init++), CAN_RX_BUF_COUNT, sizeof(struct can_msg),
+                                    RTEMS_FIFO | RTEMS_LOCAL, &bus->rx_queue_id);
+}
+
+rtems_status_code can_create_tx_buffers(struct can_bus *bus)
+{
+  if ((bus->tx_fifo.pbuf = (struct can_msg *)malloc(CAN_TX_BUF_COUNT * sizeof(struct can_msg))) == NULL) {
+    printf("malloc failed\n");
+    return RTEMS_NO_MEMORY;
+  }
+
+  bus->tx_fifo.head = bus->tx_fifo.tail = 0;
+  bus->tx_fifo.empty_count = CAN_TX_BUF_COUNT;
+
+  return 0;
+}
+
+bool can_tx_buf_isempty(struct can_bus *bus)
+{
+  if (bus->tx_fifo.empty_count <= 0) {
+    /* tx_fifo.empty_count does not go below zero, incase if it goes update to zero */
+    bus->tx_fifo.empty_count = 0;
+
+    return false;
+  }
+
+  return true;
+}
+
+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) {
+    printf("can_tx_get_next_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;
+}
+    
+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) {
+    printf("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;
+}
diff --git a/cpukit/dev/can/can.c b/cpukit/dev/can/can.c
new file mode 100644
index 0000000000..e8aa9d20ca
--- /dev/null
+++ b/cpukit/dev/can/can.c
@@ -0,0 +1,480 @@
+/* SPDX-License-Identifier: BSD-2-Clause */
+
+/**
+ * @file
+ *
+ * @ingroup CANBus
+ *
+ * @brief Controller Area Network (CAN) Bus Implementation
+ *
+ */
+
+/*
+ * Copyright (C) 2022
+ *
+ * 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.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 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);
+}
+
+static ssize_t can_bus_open(rtems_libio_t *iop, const char *path, int oflag, mode_t mode)
+{
+/*
+  static int init = 0;
+
+  if (init == 1) {
+    return 0;
+  }
+
+  init = 1;
+
+  can_bus *bus = IMFS_generic_get_context_by_iop(iop);
+
+  if (bus == NULL) {
+    return -RTEMS_NOT_DEFINED;
+  }
+
+  can_create_sem(bus);
+*/
+  return 0;
+} 
+
+int can_receive(struct can_bus *bus, struct can_msg *msg)
+{
+  int32_t ret = 0;
+
+  uint32_t count = 0;
+
+  if ((ret = rtems_message_queue_broadcast(bus->rx_queue_id, msg, sizeof(struct can_msg) - (CAN_MSG_MAX_SIZE - msg->len), &count)) != RTEMS_SUCCESSFUL) {
+    printf("rtems_message_queue_send failed\n");
+  }
+
+  printf("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;
+  }
+  
+  if ((ret = rtems_message_queue_receive(bus->rx_queue_id, (void *)msg, &count, flags, 0)) != RTEMS_SUCCESSFUL) {
+    return ret;
+  }
+
+  return count;
+}
+
+int can_create_sem(struct can_bus *bus)
+{
+  int ret = 0;
+
+#ifndef _POSIX_SEM_
+  //TODO: for test purpose
+  static int init = 0;
+
+  ret = rtems_semaphore_create(rtems_build_name('c', 'a', 'n', '0' + init++), 1, 
+      RTEMS_FIFO | RTEMS_SIMPLE_BINARY_SEMAPHORE | RTEMS_LOCAL, 0, &bus->tx_fifo_sem_id);
+
+  if (ret != 0) {
+    printf("rtems_semaphore_create failed %d\n", ret);
+    return ret;
+  }
+
+  ret = rtems_semaphore_obtain(bus->tx_fifo_sem_id, RTEMS_WAIT, RTEMS_NO_TIMEOUT);
+
+  if (ret != 0) {
+    printf("rtems_semaphore_obtain failed %d\n", ret);
+    return ret;
+  }
+#else
+  ret = sem_init(&bus->tx_sem_id, 0, 1);
+
+  if (ret != 0) {
+    printf("sem_init failed %d\n", ret);
+    return ret;
+  }
+#endif /* _POSIX_SEM_ */
+  return ret;
+}
+
+int take_sem(struct can_bus *bus)
+{
+  int ret = 0;
+
+#ifndef _POSIX_SEM_
+  ret = rtems_semaphore_obtain(bus->tx_fifo_sem_id, RTEMS_WAIT, RTEMS_NO_TIMEOUT);
+#else
+  ret = sem_wait(&bus->tx_sem_id);
+#endif /* _POSIX_SEM_ */
+
+  return ret;
+}
+
+int give_sem(struct can_bus *bus)
+{
+  int ret = 0;
+
+#ifndef _POSIX_SEM_
+  ret = rtems_semaphore_release(bus->tx_fifo_sem_id);
+#else
+  ret = sem_post(&bus->tx_sem_id);
+#endif /* _POSIX_SEM_ */
+
+  return ret;
+}
+
+static int can_xmit(struct can_bus *bus)
+{
+  int ret = 0;
+
+  struct can_msg *msg = NULL;
+
+  rtems_interrupt_lock_context lock_context;
+
+  while (1) {
+    rtems_interrupt_lock_acquire(&bus->can_bus_lock, &lock_context);
+
+    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("dev_send failed\n");
+    }
+
+    rtems_interrupt_lock_release(&bus->can_bus_lock, &lock_context);
+
+    //can_tx_done(bus);
+  }
+
+  return RTEMS_SUCCESSFUL;
+
+return_with_lock_release:
+
+  rtems_interrupt_lock_release(&bus->can_bus_lock, &lock_context);
+  return RTEMS_SUCCESSFUL;
+}
+
+void can_print_canmsg(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");
+}
+
+int can_tx_done(struct can_bus *bus)
+{
+  int ret = 0;
+
+  if (bus->can_dev_ops->dev_tx_ready(bus) == true) {
+    can_xmit(bus);
+  }
+  
+  if (bus->can_tx_buf_waiters > 0 && (can_tx_buf_isempty(bus) != 0)) {
+    ret = give_sem(bus);
+    if (ret != 0) {
+      printf(">>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>> rtems_semaphore_release failed = %d\n", ret);
+    } else {
+    }
+  }
+
+  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;
+
+  rtems_interrupt_lock_context lock_context;
+
+  while (1) {
+    /* sleep is for debug purpose to test concurrency issues */
+    sleep(1);
+
+    rtems_interrupt_lock_acquire(&bus->can_bus_lock, &lock_context);
+
+    fifo_buf = can_tx_get_empty_buf(bus);
+
+    if (fifo_buf != NULL) {
+      uint32_t msg_size = (char *)&msg->data[msg->len] - (char *)msg;
+
+      if (msg_size > sizeof(struct can_msg)) {
+        printf("can message len error msg_size = %u struct can_msg = %u\n", msg_size, sizeof(struct can_msg));
+        return -RTEMS_INVALID_SIZE;
+      }
+
+      memcpy(fifo_buf, msg, msg_size); //sizeof(struct can_msg) - (CAN_MSG_MAX_SIZE - msg->len));
+      ret = msg_size;
+      //can_print_canmsg(msg);
+    }
+
+    rtems_interrupt_lock_release(&bus->can_bus_lock, &lock_context);
+
+    /* sleep is for debug purpose to test concurrency issues */
+    sleep(1);
+
+    if (fifo_buf != NULL) {
+      break;
+    }
+
+    /* Enters if clause, if there are no empty tx fifo buffers. Based on the flags, sleep until buffer 
+     * is empty or return error status 
+     */
+  
+    if (fifo_buf == NULL) {
+      if ((iop->flags & O_NONBLOCK) != 0) {
+        return -RTEMS_RESOURCE_IN_USE;
+      }
+  
+      if (bus->can_dev_ops->dev_tx_ready(bus) == true) {
+        can_xmit(bus);
+      }
+
+      rtems_interrupt_lock_acquire(&bus->can_bus_lock, &lock_context);
+      ret = can_tx_buf_isempty(bus);
+      rtems_interrupt_lock_release(&bus->can_bus_lock, &lock_context);
+
+      if (ret == true) {
+        continue;
+      }
+
+      rtems_interrupt_lock_acquire(&bus->can_bus_lock, &lock_context);
+      bus->can_tx_buf_waiters++;
+      rtems_interrupt_lock_release(&bus->can_bus_lock, &lock_context);
+
+      printf("empty_count = %u\n", bus->tx_fifo.empty_count);
+
+      ret = take_sem(bus);
+
+      rtems_interrupt_lock_acquire(&bus->can_bus_lock, &lock_context);
+      bus->can_tx_buf_waiters--;
+      rtems_interrupt_lock_release(&bus->can_bus_lock, &lock_context);
+  
+      if (ret != RTEMS_SUCCESSFUL) {
+        printf("cannot take semaphore\n");
+        ret = -RTEMS_INTERNAL_ERROR;
+        goto return_release_lock;
+      }
+    }
+  }
+
+  if (bus->can_dev_ops->dev_tx_ready(bus) == true) {
+    can_xmit(bus);
+  }
+
+return_release_lock:
+
+  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;
+
+  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("Creating node failed: %d\n", ret);
+    goto fail;
+  }
+
+  RTEMS_INTERRUPT_LOCK_INITIALIZER(bus->can_bus_lock);
+
+  if ((ret = can_create_sem(bus)) != RTEMS_SUCCESSFUL) {
+    printf("can_create_sem failed = %d\n", ret);
+    goto fail;
+  }
+
+  if ((ret = can_create_tx_buffers(bus)) != RTEMS_SUCCESSFUL) {
+    printf("can_create_tx_buffers failed = %d\n", ret);
+    goto fail;
+  }
+
+  if ((ret = can_create_rx_buffers(bus)) != RTEMS_SUCCESSFUL) {
+    printf("can_create_rx_buffers failed = %d\n", ret);
+    goto fail;
+  }
+
+  return ret;
+
+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) {
+      int rv;
+
+      rv = can_bus_do_init(bus, can_bus_destroy_and_free);
+      if (rv != 0) {
+        return NULL;
+      }
+    }
+  }
+
+  return bus;
+}
diff --git a/cpukit/include/dev/can/can.h b/cpukit/include/dev/can/can.h
new file mode 100644
index 0000000000..2210820504
--- /dev/null
+++ b/cpukit/include/dev/can/can.h
@@ -0,0 +1,115 @@
+/* SPDX-License-Identifier: BSD-2-Clause */
+
+/**
+ * @file
+ *
+ * @ingroup CANBus
+ *
+ * @brief Controller Area Network (CAN) Bus Implementation
+ *
+ */
+
+/*
+ * Copyright (C) 2022
+ *
+ * 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>
+
+#define CAN_MSG_MAX_SIZE  (8u)
+
+#define CAN_TX_BUF_COUNT  (10u)
+#define CAN_RX_BUF_COUNT  (10u)
+
+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_tx_int)(void *priv, bool);
+  int32_t (*dev_ioctl)(void *priv, void *buffer, size_t cmd);
+} can_dev_ops;
+
+struct ring_buf {
+  struct can_msg *pbuf;
+  uint32_t head;
+  uint32_t tail;
+  uint32_t empty_count;
+};
+
+typedef struct can_bus {
+  void *priv;                               // CAN controller specific struct.
+  struct can_dev_ops *can_dev_ops;          // CAN controller operations.
+  struct ring_buf tx_fifo;                  // TX fifo
+#ifndef _POSIX_SEM_
+  rtems_id tx_fifo_sem_id;                  // TX fifo counting semaphore id
+#else
+  sem_t tx_sem_id;
+  uint32_t tx_fifo_sem_name;                // TX fifo sem name
+#endif /* _POSIX_SEM_ */
+  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;
+
+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.
+};
+
+extern can_bus *can_bus_alloc_and_init(size_t size);
+extern int can_bus_init(can_bus *bus);
+extern rtems_status_code can_bus_register(can_bus *bus, const char *bus_path);
+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 rtems_status_code can_create_tx_buffers(struct can_bus *bus);
+extern rtems_status_code can_create_rx_buffers(struct can_bus *bus);
+extern bool can_tx_buf_isempty(struct can_bus *bus);
+extern struct can_msg *can_tx_get_data_buf(struct can_bus *bus);
+extern struct can_msg *can_tx_get_empty_buf(struct can_bus *bus);
+
+extern int take_sem(struct can_bus *);
+extern int give_sem(struct can_bus *);
+extern int can_create_sem(struct can_bus *bus);
+
+extern void can_print_canmsg(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..b700935f82 100644
--- a/spec/build/cpukit/librtemscpu.yml
+++ b/spec/build/cpukit/librtemscpu.yml
@@ -50,6 +50,9 @@ 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
 - destination: ${BSP_INCLUDEDIR}/linux
   source:
   - cpukit/include/linux/i2c-dev.h
@@ -530,6 +533,8 @@ source:
 - cpukit/dev/serial/sc16is752-spi.c
 - cpukit/dev/serial/sc16is752.c
 - cpukit/dev/spi/spi-bus.c
+- cpukit/dev/can/can.c
+- cpukit/dev/can/can-queue.c
 - cpukit/dtc/libfdt/fdt.c
 - cpukit/dtc/libfdt/fdt_addresses.c
 - cpukit/dtc/libfdt/fdt_empty_tree.c
-- 
2.25.1



More information about the devel mailing list