micro-ROS/micro_ros_stm32cubemx_utils

Multiple Nodes

wen-da opened this issue · 2 comments

Hi, is there any example or support for multiple nodes?

I have 2 FreeRTOS tasks, each of them is hosting 1 node. Both FreeRTOS tasks are using the same U(S)ART DMA (ie: usart4).

However, when I run the micro_ros_agent on the workstation, it only detects 1 node with the following behavior :

  • Both nodes are correctly set up and fully functional when only 1 node is being run.
  • The FreeRTOS task that has the higher priority tend to be detected by the micro_ros_agent.
  • When hosting both 2 nodes in 1 FreeRTOS task, the first mentioned node tend to be detected by the micro_ros_agent.

Below is the "colcon.meta" which I have set the "-DRMW_UXRCE_MAX_NODES" to 2.

{
    "names": {
        "tracetools": {
            "cmake-args": [
                "-DTRACETOOLS_DISABLED=ON",
                "-DTRACETOOLS_STATUS_CHECKING_TOOL=OFF"
            ]
        },
        "rosidl_typesupport": {
            "cmake-args": [
                "-DROSIDL_TYPESUPPORT_SINGLE_TYPESUPPORT=ON"
            ]
        },
        "rcl": {
            "cmake-args": [
                "-DBUILD_TESTING=OFF",
                "-DRCL_COMMAND_LINE_ENABLED=OFF",
                "-DRCL_LOGGING_ENABLED=OFF"
            ]
        },
        "rcutils": {
            "cmake-args": [
                "-DENABLE_TESTING=OFF",
                "-DRCUTILS_NO_FILESYSTEM=ON",
                "-DRCUTILS_NO_THREAD_SUPPORT=ON",
                "-DRCUTILS_NO_64_ATOMIC=ON",
                "-DRCUTILS_AVOID_DYNAMIC_ALLOCATION=ON"
            ]
        },
        "microxrcedds_client": {
            "cmake-args": [
                "-DUCLIENT_PIC=OFF",
                "-DUCLIENT_PROFILE_UDP=OFF",
                "-DUCLIENT_PROFILE_TCP=OFF",
                "-DUCLIENT_PROFILE_DISCOVERY=OFF",
                "-DUCLIENT_PROFILE_SERIAL=OFF",
                "-UCLIENT_PROFILE_STREAM_FRAMING=ON",
                "-DUCLIENT_PROFILE_CUSTOM_TRANSPORT=ON"
            ]
        },
        "rmw_microxrcedds": {
            "cmake-args": [
                "-DRMW_UXRCE_MAX_NODES=2",
                "-DRMW_UXRCE_MAX_PUBLISHERS=10",
                "-DRMW_UXRCE_MAX_SUBSCRIPTIONS=5",
                "-DRMW_UXRCE_MAX_SERVICES=1",
                "-DRMW_UXRCE_MAX_CLIENTS=1",
                "-DRMW_UXRCE_MAX_HISTORY=4",
                "-DRMW_UXRCE_TRANSPORT=custom"
            ]
        }
    }
}

Can someone please guide me on this?

micro-ROS is not thread-safe by default. The recommended option for this use case is using a single node in a single task.

OK, here's an update.
First of all, using the same USART on 2 different FreeRTOS tasks was a bad idea to begin with. You can use mutexes but that would be a bit complex for an initial build. Therefore, if you have to have 2 different FreeRTOS tasks hosting 2 different nodes for some reason... better use 2 different USART port, it is a lot more straight forward and approachable.

Or else, try multi-threading with multi-core STM32 boards.

I instead use only 1 FreeRTOS task to host everything. Still creating multiple nodes with multiple topics. The publishers are slightly delayed from each other as the number of publisher scale up. If this is what you're looking for, this is how I setup multiple nodes multiple topics (open for more examples and better suggestions 🙏 Thanks!) :

	/* Initialize micro-ROS node1 */
	rcl_node_t node1;
	rcl_allocator_t allocator = rcl_get_default_allocator();
	rclc_support_t support;

	if(RCL_RET_OK != rclc_support_init(&support, 0, NULL, &allocator)){
		printf("Failed to initialize support (line %d) \n", __LINE__);
	}
	if(RCL_RET_OK != rclc_node_init_default(&node1, "node1", "", &support)){
		printf("Failed to initialize node1 (line %d) \n", __LINE__);
	}

	/* Setup publisher1 for node1 */
	publisher_msg1.data = 0;
	rcl_publisher_t publisher1;
	if(RCL_RET_OK != rclc_publisher_init_default(
			&publisher1,
			&node1,
			ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
			"publisher1")){
		printf("Failed to create publisher (line %d) \n", __LINE__);
	}

	/* Setup subscriber1 for node1 */
	rcl_subscription_t subscriber1;
	if(RCL_RET_OK != rclc_subscription_init_default(
			&subscriber1,
			&node1,
			ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
			"subscriber1")){
		printf("Failed to create subscriber1 (line %d) \n", __LINE__);
	}


	/* Initialize micro-ROS node2 */
	rcl_node_t node2;
	if(RCL_RET_OK != rclc_node_init_default(&node2, "node2", "", &support)){
		printf("Failed to initialize node2 (line %d) \n", __LINE__);
	}

	/* Setup publisher2 for node2*/
	rcl_publisher_t publisher2;
	publisher_msg2.data = 0;
	if(RCL_RET_OK != rclc_publisher_init_default(
			&publisher2,
			&node2,
			ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
			"publisher2")){
		printf("Failed to create publisher2 (line %d) \n", __LINE__);
	}

	/* Setup subscriber2 for node2*/
	rcl_subscription_t subscriber2;
	if(RCL_RET_OK != rclc_subscription_init_default(
			&subscriber2,
			&node2,
			ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32),
			"subscriber2")){
		printf("Failed to create subscriber2 (line %d) \n", __LINE__);
	}

	/* Setup executor for handling subscription callback */
	rclc_executor_t executor = rclc_executor_get_zero_initialized_executor();

	if(RCL_RET_OK != rclc_executor_init(&executor, &support.context, 2, &allocator)){
		printf("Failed to initialize executor (line %d) \n", __LINE__);
	}

	if(RCL_RET_OK != rclc_executor_add_subscription(
			&executor,
			&subscriber1,
			&subscriber_msg1,
			&subscriber_callback,
			ON_NEW_DATA)){
		printf("Failed to add subscription to executor (line %d) \n", __LINE__);
	}

	if(RCL_RET_OK != rclc_executor_add_subscription(
			&executor,
			&subscriber2,
			&subcriber_msg2,
			&subscriber_callback,
			ON_NEW_DATA)){
		printf("Failed to add subscription to executor (line %d) \n", __LINE__);
	}

Inside the infinite loop

  /* Infinite loop */
  for(;;)
  {
	  publisher_msg1.data++;
	  publisher_msg2.data++;

	  if (RCL_RET_OK != rcl_publish(&publisher1, &publisher_msg1, NULL)){
		printf("Error publishing (line %d)\n", __LINE__);
	  }

	  if (RCL_RET_OK != rcl_publish(&publisher2, &publisher_msg2, NULL)){
		printf("Error publishing (line %d)\n", __LINE__);
	  }
	  
	  rclc_executor_spin_some(&executor, RCL_MS_TO_NS(1));
	  osDelay(1);
  }