|
| 1 | +--- |
| 2 | +title: How to use custom QoS in micro-ROS |
| 3 | +permalink: /docs/tutorials/core/create_dds_entities_by_ref/ |
| 4 | +--- |
| 5 | + |
| 6 | + |
| 7 | +This tutorial explains the procedure for creating micro-ROS entities using fully configurable QoS settings. The micro-ROS default middleware (Micro XRCE-DDS Client) allows the user to take two different approaches for creating ROS 2 (DDS) entities in the micro-ROS Agent (Please check the [architecture section](https://micro-ros.github.io/docs/overview/) for detailed information): |
| 8 | +- By XML (the default option in micro-ROS RMW) |
| 9 | +- By reference |
| 10 | + |
| 11 | +Using the *default option* the micro-ROS user will be able to create entities using RCLC functions such as `rclc_publisher_init_default` for reliable communications or `rclc_publisher_init_best_effort` for best effort communications. Please check [RCLC](https://github.com/micro-ROS/rclc) for an updated list of convenience functions. |
| 12 | + |
| 13 | +For those familiar with the QoS XML format in DDS (click [here](https://fast-dds.docs.eprosima.com/en/latest/fastdds/dds_layer/core/policy/policy.html) for detailed information), the underlying QoS profile used by this default mode looks like this: |
| 14 | + |
| 15 | +```xml |
| 16 | +<!-- TOPIC --> |
| 17 | +<dds> |
| 18 | + <topic> |
| 19 | + <name>[TOPIC NAME]</name> |
| 20 | + <dataType>[TOPIC TYPE]</dataType> |
| 21 | + </topic> |
| 22 | +</dds> |
| 23 | + |
| 24 | +<!-- DATA WRITER --> |
| 25 | +<dds> |
| 26 | + <data_writer> |
| 27 | + <historyMemoryPolicy>PREALLOCATED_WITH_REALLOC</historyMemoryPolicy> |
| 28 | + <qos> |
| 29 | + <reliability> |
| 30 | + <kind>[WRITER RELIABILITY]</kind> |
| 31 | + </reliability> |
| 32 | + </qos> |
| 33 | + <topic> |
| 34 | + <kind>NO_KEY</kind> |
| 35 | + <name>[WRITER NAME]</name> |
| 36 | + <dataType>[WRITER TYPE]</dataType> |
| 37 | + <historyQos> |
| 38 | + <kind>KEEP_ALL</kind> |
| 39 | + </historyQos> |
| 40 | + </topic> |
| 41 | + </data_writer> |
| 42 | +</dds> |
| 43 | + |
| 44 | +<!-- DATA READER --> |
| 45 | +<dds> |
| 46 | + <data_reader> |
| 47 | + <historyMemoryPolicy>PREALLOCATED_WITH_REALLOC</historyMemoryPolicy> |
| 48 | + <qos> |
| 49 | + <reliability> |
| 50 | + <kind>[READER RELIABILITY]</kind> |
| 51 | + </reliability> |
| 52 | + </qos> |
| 53 | + <topic> |
| 54 | + <kind>NO_KEY</kind> |
| 55 | + <name>[READER NAME]</name> |
| 56 | + <dataType>[READER TYPE]</dataType> |
| 57 | + <historyQos> |
| 58 | + <kind>KEEP_ALL</kind> |
| 59 | + </historyQos> |
| 60 | + </topic> |
| 61 | + </data_reader> |
| 62 | +</dds> |
| 63 | + |
| 64 | +``` |
| 65 | + |
| 66 | +But these QoS configurations may not fit some user's requirements. For these cases, micro-ROS allows the users to write their custom XML QoS and run the agent with a predefined set of QoS. Each entity will have its own label and the micro-ROS client will create the entities using just this reference. |
| 67 | + |
| 68 | +Additionally, using references will also reduce the memory consumption of the micro-ROS client inside the MCU. This is because the parts of the code where XML are handled are just not build with the references approach. |
| 69 | + |
| 70 | +Let's see how to create a micro-ROS node that creates entities with custom QoS. First of all, independently of which RTOS you have selected in [First micro-ROS Application on an RTOS |
| 71 | +](https://micro-ros.github.io/docs/tutorials/core/first_application_rtos/) tutorial, you should have an app configuration file named `app-colcon.meta`. |
| 72 | + |
| 73 | +Inside this `app-colcon.meta` file we can set application specific CMake options for the micro-ROS packages that are going to be crosscompiled. So, let's setup the `rmw_microxrcedds` in order to use references; your `app-colcon.meta` should look like this: |
| 74 | + |
| 75 | +``` |
| 76 | +{ |
| 77 | + "names": { |
| 78 | + "rmw_microxrcedds": { |
| 79 | + "cmake-args": [ |
| 80 | + ... |
| 81 | + "-DRMW_UXRCE_CREATION_MODE=refs" |
| 82 | + ... |
| 83 | + ] |
| 84 | + } |
| 85 | + } |
| 86 | +} |
| 87 | +``` |
| 88 | + |
| 89 | +Of course you can combine these configurations with others, e.g. the ones described in the [Middleware Configuration](https://micro-ros.github.io/docs/tutorials/core/microxrcedds_rmw_configuration/) tutorial. |
| 90 | + |
| 91 | +Once you have this parameter, write your micro-ROS application using RCLC default convenience functions. Just remember that now you are not providing the topic name but a "QoS reference label": |
| 92 | + |
| 93 | +```c |
| 94 | +#include <std_msgs/msg/int32.h> |
| 95 | + |
| 96 | +... |
| 97 | + |
| 98 | +std_msgs__msg__Int32 msg; |
| 99 | + |
| 100 | +msg.data = 42; |
| 101 | + |
| 102 | +... |
| 103 | + |
| 104 | +rclc_publisher_init_default(&publisher, &node, ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int32), "my_qos_label"); |
| 105 | +rcl_publish(&publisher, &msg, NULL); |
| 106 | + |
| 107 | +... |
| 108 | +``` |
| 109 | +
|
| 110 | +This code will tell the micro-ROS Agent to create a publisher using just a text label: `my_qos_label`. This implies that the micro-ROS Agent must have a file where these labels are written along with some QoS profiles. Let's create a `custom_qos.refs` with the following content: |
| 111 | +
|
| 112 | +```xml |
| 113 | +<profiles> |
| 114 | + <participant profile_name="participant_profile"> |
| 115 | + <rtps> |
| 116 | + <name>default_xrce_participant</name> |
| 117 | + </rtps> |
| 118 | + </participant> |
| 119 | +
|
| 120 | + <topic profile_name="my_qos_label__t"> |
| 121 | + <name>rt/my_topic_name</name> |
| 122 | + <dataType>std_msgs::msg::dds_::Int32_</dataType> |
| 123 | + <historyQos> |
| 124 | + <kind>KEEP_LAST</kind> |
| 125 | + <depth>20</depth> |
| 126 | + </historyQos> |
| 127 | + </topic> |
| 128 | +
|
| 129 | + <data_writer profile_name="my_qos_label__dw"> |
| 130 | + <historyMemoryPolicy>PREALLOCATED_WITH_REALLOC</historyMemoryPolicy> |
| 131 | + <qos> |
| 132 | + <reliability> |
| 133 | + <kind>RELIABLE</kind> |
| 134 | + </reliability> |
| 135 | + </qos> |
| 136 | + <topic> |
| 137 | + <kind>NO_KEY</kind> |
| 138 | + <name>rt/my_topic_name</name> |
| 139 | + <dataType>std_msgs::msg::dds_::Int32_</dataType> |
| 140 | + <historyQos> |
| 141 | + <kind>KEEP_LAST</kind> |
| 142 | + <depth>20</depth> |
| 143 | + </historyQos> |
| 144 | + </topic> |
| 145 | + </data_writer> |
| 146 | +
|
| 147 | +</profiles> |
| 148 | +``` |
| 149 | + |
| 150 | +When writting this XML file, special care about ROS2 to DDS name mangling has to be taken into account. Read more information about this [here](http://design.ros2.org/articles/topic_and_service_names.html#mapping-of-ros-2-topic-and-service-names-to-dds-concepts). |
| 151 | + |
| 152 | +Once you have this file ready, just run the micro-ROS agent with the `-r` parameter: |
| 153 | + |
| 154 | +``` |
| 155 | +ros2 run micro_ros_agent micro_ros_agent [PARAMETERS] -r custom_qos.refs |
| 156 | +``` |
| 157 | + |
| 158 | +Once the entities are created and the topic is being published, you can check the QoS using: |
| 159 | + |
| 160 | +``` |
| 161 | +$ ros2 topic info /std_msgs_msg_Int32 --verbose |
| 162 | +Type: std_msgs/msg/Int32 |
| 163 | +
|
| 164 | +Publisher count: 1 |
| 165 | +
|
| 166 | +Node name: _CREATED_BY_BARE_DDS_APP_ |
| 167 | +Node namespace: _CREATED_BY_BARE_DDS_APP_ |
| 168 | +Topic type: std_msgs/msg/Int32 |
| 169 | +Endpoint type: PUBLISHER |
| 170 | +GID: 01.0f.0b.5c.8b.7d.00.00.01.00.00.00.00.00.01.03.00.00.00.00.00.00.00.00 |
| 171 | +QoS profile: |
| 172 | + Reliability: RMW_QOS_POLICY_RELIABILITY_RELIABLE |
| 173 | + Durability: RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL |
| 174 | + Lifespan: 2147483651294967295 nanoseconds |
| 175 | + Deadline: 2147483651294967295 nanoseconds |
| 176 | + Liveliness: RMW_QOS_POLICY_LIVELINESS_AUTOMATIC |
| 177 | + Liveliness lease duration: 2147483651294967295 nanoseconds |
| 178 | +
|
| 179 | +Subscription count: 0 |
| 180 | +``` |
0 commit comments