pkarashchenko commented on code in PR #1558:
URL: https://github.com/apache/nuttx-apps/pull/1558#discussion_r1141792546


##########
canutils/libdronecan/Kconfig:
##########
@@ -0,0 +1,37 @@
+#
+# For a description of the syntax of this configuration file,
+# see the file kconfig-language.txt in the NuttX tools repository.
+#
+
+config CANUTILS_LIBDRONECAN
+       bool "libcanard DroneCAN Library"
+       default n
+       depends on (CAN && CAN_EXTID) || NET_CAN
+       ---help---
+               Enable the libcanard DroneCAN library.
+
+if CANUTILS_LIBDRONECAN
+
+config LIBDRONECAN_URL
+       string "libcanard URL"
+       default "https://github.com/dronecan/libcanard/archive";
+       ---help---
+               libcanard URL.
+
+config LIBDRONECAN_VERSION
+       string "libcanard Version"
+       default "21f2a73df86886101e254d02cfc2277cd2a15717"
+       ---help---
+               libcanard version.
+               
+config LIBDRONECAN_CANFD
+       bool "(Experimental) libcanard CAN FD Support"
+       default n
+       depends on NET_CAN_CANFD

Review Comment:
   Do we need `depends on EXPERIMENTAL`?



##########
canutils/libdronecan/Make.defs:
##########
@@ -18,6 +18,13 @@
 #
 ############################################################################
 
-ifneq ($(CONFIG_CANUTILS_LIBCANARDV0),)
-CONFIGURED_APPS += $(APPDIR)/canutils/libcanardv0
+ifneq ($(CONFIG_CANUTILS_LIBDRONECAN),)
+CONFIGURED_APPS += $(APPDIR)/canutils/libdronecan
+
+

Review Comment:
   ```suggestion
   ```



##########
canutils/libopencyphal/Make.defs:
##########
@@ -18,6 +18,11 @@
 #
 ############################################################################
 
-ifneq ($(CONFIG_CANUTILS_LIBCANARDV1),)
-CONFIGURED_APPS += $(APPDIR)/canutils/libcanardv1
+ifneq ($(CONFIG_CANUTILS_LIBOPENCYPHAL),)
+CONFIGURED_APPS += $(APPDIR)/canutils/libopencyphal
+
+

Review Comment:
   ```suggestion
   ```



##########
examples/dronecan/canard_main.c:
##########
@@ -372,17 +414,24 @@ void process1HzTasks(uint64_t timestamp_usec)
  *   Transmits all frames from the TX queue, receives up to one frame.
  *
  ****************************************************************************/
-
+#ifdef CONFIG_NET_CAN
+void processTxRxOnce(SocketCANInstance  * socketcan, int timeout_msec)

Review Comment:
   ```suggestion
   void processTxRxOnce(SocketCANInstance *socketcan, int timeout_msec)
   ```



##########
examples/dronecan/canard_main.c:
##########
@@ -227,6 +241,17 @@ static void onTransferReceived(CanardInstance *ins,
        */
 
       const int resp_res =
+#if CANARD_ENABLE_CANFD
+        canardRequestOrRespond(ins,
+                               transfer->source_node_id,
+                               UAVCAN_GET_NODE_INFO_DATA_TYPE_SIGNATURE,
+                               UAVCAN_GET_NODE_INFO_DATA_TYPE_ID,
+                               &transfer->transfer_id,
+                               transfer->priority,
+                               CanardResponse,
+                               &buffer[0],
+                               (uint16_t) total_size, canfd);

Review Comment:
   ```suggestion
                                  (uint16_t)total_size, canfd);
   ```



##########
examples/dronecan/canard_main.c:
##########
@@ -115,6 +125,10 @@ static uint8_t node_health = UAVCAN_NODE_HEALTH_OK;
 static uint8_t node_mode = UAVCAN_NODE_MODE_INITIALIZATION;
 static bool g_canard_daemon_started;
 
+#if CANARD_ENABLE_CANFD
+static bool canfd = false;

Review Comment:
   ```suggestion
   static bool canfd;
   ```



##########
examples/dronecan/canard_main.c:
##########
@@ -429,30 +482,50 @@ void processTxRxOnce(CanardNuttXInstance * nuttxcan, int 
timeout_msec)
 
 static int canard_daemon(int argc, char *argv[])
 {
+#ifdef CONFIG_NET_CAN
+  static SocketCANInstance socketcan;
+#else
   static CanardNuttXInstance canardnuttx_instance;
+  int ret;
+#endif
 #ifdef CONFIG_DEBUG_CAN
   struct canioc_bittiming_s bt;
 #endif
   int errval = 0;
-  int ret;
 
   /* Initialization of the CAN hardware is performed by external, board-
    * specific logic to running this test.
    */
 
   /* Open the CAN device for reading */
 
+  
+#ifdef CONFIG_NET_CAN
+  const char *const can_iface_name = "can0";

Review Comment:
   ```suggestion
     const char * const can_iface_name = "can0";
   ```



##########
examples/opencyphal/canard_main.c:
##########
@@ -326,7 +326,7 @@ static int canard_daemon(int argc, char *argv[])
   if (sock_ins.s < 0)
     {
       printf("canard_daemon: ERROR: open %s failed: %d\n",
-         CONFIG_EXAMPLES_LIBCANARDV1_DEV, errno);
+         CONFIG_EXAMPLES_LIBOPENCYPHAL_DEV, errno);

Review Comment:
   please align with upper `(`



##########
examples/dronecan/canard_main.c:
##########
@@ -525,9 +604,14 @@ int main(int argc, FAR char *argv[])
       return EXIT_SUCCESS;
     }
 
+  if (argc == 2 && strcmp(argv[1],"canfd") == 0) {

Review Comment:
   ```suggestion
     if (argc == 2 && strcmp(argv[1], "canfd") == 0)
       {
   ```



##########
examples/dronecan/canard_main.c:
##########
@@ -429,30 +482,50 @@ void processTxRxOnce(CanardNuttXInstance * nuttxcan, int 
timeout_msec)
 
 static int canard_daemon(int argc, char *argv[])
 {
+#ifdef CONFIG_NET_CAN
+  static SocketCANInstance socketcan;
+#else
   static CanardNuttXInstance canardnuttx_instance;
+  int ret;
+#endif
 #ifdef CONFIG_DEBUG_CAN
   struct canioc_bittiming_s bt;
 #endif
   int errval = 0;
-  int ret;
 
   /* Initialization of the CAN hardware is performed by external, board-
    * specific logic to running this test.
    */
 
   /* Open the CAN device for reading */
 
+  
+#ifdef CONFIG_NET_CAN
+  const char *const can_iface_name = "can0";
+
+#  if CANARD_ENABLE_CANFD
+  int16_t res = socketcanInit(&socketcan, can_iface_name, canfd);
+#  else
+  int16_t res = socketcanInit(&socketcan, can_iface_name);
+#  endif
+  if (res < 0)
+    {
+      (void)fprintf(stderr, "Failed to open CAN iface '%s'\n", can_iface_name);

Review Comment:
   Why need `(void)` cast here?



##########
examples/dronecan/canard_main.c:
##########
@@ -372,17 +414,24 @@ void process1HzTasks(uint64_t timestamp_usec)
  *   Transmits all frames from the TX queue, receives up to one frame.
  *
  ****************************************************************************/
-
+#ifdef CONFIG_NET_CAN
+void processTxRxOnce(SocketCANInstance  * socketcan, int timeout_msec)
+#else
 void processTxRxOnce(CanardNuttXInstance * nuttxcan, int timeout_msec)

Review Comment:
   ```suggestion
   void processTxRxOnce(CanardNuttXInstance *nuttxcan, int timeout_msec)
   ```



-- 
This is an automated message from the Apache Git Service.
To respond to the message, please log on to GitHub and use the
URL above to go to the specific comment.

To unsubscribe, e-mail: [email protected]

For queries about this service, please contact Infrastructure at:
[email protected]

Reply via email to