You can not select more than 25 topics Topics must start with a chinese character,a letter or number, can include dashes ('-') and can be up to 35 characters long.

README.md 12 kB

1 year ago
123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321
  1. # Dora Node API for C++
  2. Dora supports nodes written in C++ through this API crate.
  3. ## Build
  4. - Clone the `dora` repository:
  5. ```bash
  6. > git clone https://github.com/dora-rs/dora.git
  7. > cd dora
  8. ```
  9. - Build the `dora-node-api-cxx` package:
  10. ```bash
  11. cargo build --package dora-node-api-cxx
  12. ```
  13. - This will result in `dora-node-api.h` and `dora-node-api.cc` files in the `target/cxxbridge/dora-node-api-cxx` directory.
  14. - Include the `dora-node-api.h` header file in your source file.
  15. - Add the `dora-node-api.cc` file to your compile and link steps.
  16. ### Build with ROS2 Bridge
  17. Dora features an experimental ROS2 Bridge that enables dora nodes to publish and subscribe to ROS2 topics.
  18. To enable the bridge, use these steps:
  19. - Clone the `dora` repository (see above).
  20. - Source the ROS2 setup files (see [ROS2 docs](https://docs.ros.org/en/rolling/Tutorials/Beginner-CLI-Tools/Configuring-ROS2-Environment.html#source-the-setup-files))
  21. - Optional: Source package-specific ROS2 setup files if you want to use custom package-specific ROS2 messages in the bridge (see [ROS2 docs](https://docs.ros.org/en/rolling/Tutorials/Beginner-Client-Libraries/Creating-Your-First-ROS2-Package.html#source-the-setup-file))
  22. - Build the `dora-node-api-cxx` package **with the `ros2-bridge` feature enabled**:
  23. ```bash
  24. cargo build --package dora-node-api-cxx --features ros2-bridge
  25. ```
  26. - In addition to the `dora-node-api.h` and `dora-node-api.cc` files, this will place a `dora-ros2-bindings.h` and a `dora-ros2-bindings.cc` file in the `target/cxxbridge/dora-node-api-cxx` directory.
  27. - Include both the `dora-node-api.h` and the `dora-ros2-bindings.h` header files in your source file.
  28. - Add the `dora-node-api.cc` and `dora-ros2-bindings.cc` files to your compile and link steps.
  29. ## Usage
  30. The `dora-node-api.h` header provides various functions to interact with Dora.
  31. ### Init Dora Node
  32. All nodes need to register themselves with Dora at startup.
  33. To do that, call the `init_dora_node()` function.
  34. The function returns a `DoraNode` instance, which gives access to dora events and enables sending Dora outputs.
  35. ```c++
  36. auto dora_node = init_dora_node();
  37. ```
  38. ### Receiving Events
  39. The `dora_node.events` field is a stream of incoming events.
  40. To wait for the next incoming event, call `dora_node.events->next()`:
  41. ```c++
  42. auto event = dora_node.events->next();
  43. ```
  44. The `next` function returns an opaque `DoraEvent` type, which cannot be inspected from C++ directly.
  45. Instead, use the following functions to read and destructure the event:
  46. - `event_type(event)` returns a `DoraEventType`, which describes the kind of event. For example, an event could be an input or a stop instruction.
  47. - when receiving a `DoraEventType::AllInputsClosed`, the node should exit and not call `next` anymore
  48. - Events of type `DoraEventType::Input` can be downcasted using `event_as_input`:
  49. ```c++
  50. auto input = event_as_input(std::move(event));
  51. ```
  52. The function returns a `DoraInput` instance, which has an `id` and `data` field.
  53. - The input `id` can be converted to a C++ string through `std::string(input.id)`.
  54. - The `data` of inputs is currently of type [`rust::Vec<uint8_t>`](https://cxx.rs/binding/vec.html). Use the provided methods for reading or converting the data.
  55. - **Note:** In the future, we plan to change the data type to the [Apache Arrow](https://arrow.apache.org/) data format to support typed inputs.
  56. ### Sending Outputs
  57. Nodes can send outputs using the `send_output` output function and the `dora_node.send_output` field.
  58. Note that all outputs need to be listed in the dataflow YAML declaration file, otherwise an error will occur.
  59. **Example:**
  60. ```c++
  61. // the data you want to send (NOTE: only byte vectors are supported right now)
  62. std::vector<uint8_t> out_vec{42};
  63. // create a Rust slice from the output vector
  64. rust::Slice<const uint8_t> out_slice{out_vec.data(), out_vec.size()};
  65. // send the slice as output
  66. auto result = send_output(dora_node.send_output, "output_id", out_slice);
  67. // check for errors
  68. auto error = std::string(result.error);
  69. if (!error.empty())
  70. {
  71. std::cerr << "Error: " << error << std::endl;
  72. return -1;
  73. }
  74. ```
  75. ## Using the ROS2 Bridge
  76. The `dora-ros2-bindings.h` contains function and struct definitions that allow interacting with ROS2 nodes.
  77. Currently, the bridge supports publishing and subscribing to ROS2 topics.
  78. In the future, we plan to support ROS2 services and ROS2 actions as well.
  79. ### Initializing the ROS2 Context
  80. The first step is to initialize a ROS2 context:
  81. ```c++
  82. auto ros2_context = init_ros2_context();
  83. ```
  84. ### Creating Nodes
  85. After initializing a ROS2 context, you can use it to create ROS2 nodes:
  86. ```c++
  87. auto node = ros2_context->new_node("/ros2_demo", "turtle_teleop");
  88. ```
  89. The first argument is the namespace of the node and the second argument is its name.
  90. ### Creating Topics
  91. After creating a node, you can use one of the `create_topic_<TYPE>` functions to create a topic on it.
  92. The `<TYPE>` describes the message type that will be sent on the topic.
  93. The Dora ROS2 bridge automatically creates `create_topic_<TYPE>` functions for all messages types found in the sourced ROS2 environment.
  94. ```c++
  95. auto vel_topic = node->create_topic_geometry_msgs_Twist("/turtle1", "cmd_vel", qos_default());
  96. ```
  97. The first argument is the namespace of the topic and the second argument is its name.
  98. The third argument is the QoS (quality of service) setting for the topic.
  99. It can be adjusted as desired, for example:
  100. ```c++
  101. auto qos = qos_default();
  102. qos.durability = Ros2Durability::Volatile;
  103. qos.liveliness = Ros2Liveliness::Automatic;
  104. auto vel_topic = node->create_topic_geometry_msgs_Twist("/turtle1", "cmd_vel", qos);
  105. ```
  106. ### Publish
  107. After creating a topic, it is possible to publish messages on it.
  108. First, create a publisher:
  109. ```c++
  110. auto vel_publisher = node->create_publisher(vel_topic, qos);
  111. ```
  112. The returned publisher is typed by the chosen topic.
  113. It will only accept messages of the topic's type, otherwise a compile error will occur.
  114. After creating a publisher, you can use the `publish` function to publish one or more messages.
  115. For example:
  116. ```c++
  117. geometry_msgs::Twist twist = {
  118. .linear = {.x = 1, .y = 0, .z = 0},
  119. .angular = {.x = 0, .y = 0, .z = 0.5}
  120. };
  121. vel_publisher->publish(twist);
  122. ```
  123. The `geometry_msgs::Twist` struct is automatically generated from the sourced ROS2 environment.
  124. Since the publisher is typed, its `publish` method only accepts `geometry_msgs::Twist` messages.
  125. ### Subscriptions
  126. Subscribing to a topic is possible through the `create_subscription` function on nodes:
  127. ```c++
  128. auto pose_topic = node->create_topic_turtlesim_Pose("/turtle1", "pose", qos_default());
  129. auto pose_subscription = node->create_subscription(pose_topic, qos_default(), event_stream);
  130. ```
  131. The `topic` is the topic you want to subscribe to, created using a `create_topic_<TYPE>` function.
  132. The second argument is the quality of service setting, which can be customized as described above.
  133. The third parameter is the event stream that the received messages should be merged into.
  134. Multiple subscriptions can be merged into the same event stream.
  135. #### Combined Event Streams
  136. Combined event streams enable the merging of multiple event streams into one.
  137. The combined stream will then deliver messages from all sources, in order of arrival.
  138. You can create such a event stream from Dora's event stream using the `dora_events_into_combined` function:
  139. ```c++
  140. auto event_stream = dora_events_into_combined(std::move(dora_node.events));
  141. ```
  142. Alternatively, if you don't want to use Dora, you can also create an empty event stream:
  143. ```c++
  144. auto event_stream = empty_combined_events();
  145. ```
  146. **Note:** You should only use `empty_combined_events` if you're running your executable independent of Dora.
  147. Ignoring the events from the `dora_node.events` channel can result in unintended behavior.
  148. #### Receiving Messages from Combined Event Stream
  149. The merged event stream will receive all incoming events of the node, including Dora events and ROS2 messages.
  150. To wait for the next incoming event, use its `next` method:
  151. ```c++
  152. auto event = event_stream.next();
  153. ```
  154. This returns a `event` instance of type `CombinedEvent`, which can be downcasted to Dora events or ROS2 messages.
  155. To handle an event, you should check it's type and then downcast it:
  156. - To check for a Dora event, you can use the `is_dora()` function. If it returns `true`, you can downcast the combined event to a Dora event using the `downcast_dora` function.
  157. - ROS2 subscriptions support a `matches` function to check whether a combined event is an instance of the respective ROS2 subscription. If it returns true, you can downcast the event to the respective ROS2 message struct using the subscription's `downcast` function.
  158. **Example:**
  159. ```c++
  160. if (event.is_dora())
  161. {
  162. auto dora_event = downcast_dora(std::move(event));
  163. // handle dora_event as described above
  164. auto ty = event_type(dora_event);
  165. if (ty == DoraEventType::Input)
  166. {
  167. auto input = event_as_input(std::move(dora_event));
  168. // etc
  169. }
  170. // .. else if
  171. }
  172. else if (pose_subscription->matches(event))
  173. {
  174. auto pose = pose_subscription->downcast(std::move(event));
  175. std::cout << "Received pose x:" << pose.x << ", y:" << pose.y << std::endl;
  176. }
  177. else
  178. {
  179. std::cout << "received unexpected event" << std::endl;
  180. }
  181. ```
  182. ### Constants
  183. Some ROS2 message definitions define constants, e.g. to specify the values of an enum-like integer field.
  184. The Dora ROS2 bridge exposes these constants in the generated bindings as functions.
  185. For example, the `STATUS_NO_FIX` constant of the [`NavSatStatus` message](https://docs.ros.org/en/jade/api/sensor_msgs/html/msg/NavSatStatus.html) can be accessed as follows:
  186. ```c++
  187. assert((sensor_msgs::const_NavSatStatus_STATUS_NO_FIX() == -1));
  188. ```
  189. (Note: Exposing them as C++ constants is not possible because it's [not supported by `cxx` yet](https://github.com/dtolnay/cxx/issues/1051).)
  190. ### Service Clients
  191. To create a service client, use one of the `create_client_<TYPE>` functions.
  192. The `<TYPE>` describes the service type, which specifies the request and response types.
  193. The Dora ROS2 bridge automatically creates `create_client_<TYPE>` functions for all service types found in the sourced ROS2 environment.
  194. ```c++
  195. auto add_two_ints = node->create_client_example_interfaces_AddTwoInts(
  196. "/",
  197. "add_two_ints",
  198. qos,
  199. merged_events
  200. );
  201. ```
  202. - The first argument is the namespace of the service and the second argument is its name.
  203. - The third argument is the QoS (quality of service) setting for the service.
  204. It can be set to `qos_default()` or adjusted as desired, for example:
  205. ```c++
  206. auto qos = qos_default();
  207. qos.reliable = true;
  208. qos.max_blocking_time = 0.1;
  209. qos.keep_last = 1;
  210. ```
  211. - The last argument is the [combined event stream](#combined-event-streams) that the received service responses should be merged into.
  212. #### Waiting for the Service
  213. In order to achieve reliable service communication, it is recommended to wait until the service is available before sending requests.
  214. Use the `wait_for_service()` method for that, e.g.:
  215. ```c++
  216. add_two_ints->wait_for_service(node)
  217. ```
  218. The given `node` must be the node on which the service was created.
  219. #### Sending Requests
  220. To send a request, use the `send_request` method:
  221. ```c++
  222. add_two_ints->send_request(request);
  223. ```
  224. The method sends the request asynchronously without waiting for a response.
  225. When the response is received, it is automatically sent to the [combined event stream](#combined-event-streams) that was given on client creation.
  226. #### Receiving Responses
  227. See the [_"Receiving Messages from Combined Event Stream"_](#receiving-messages-from-combined-event-stream) section for how to receive events from the combined event stream.
  228. To check if a received event is a service response, use the `matches` method.
  229. If it returns `true`, you can use the `downcast` method to convert the event to the correct service response type.
  230. Example:
  231. ```c++
  232. if (add_two_ints->matches(event))
  233. {
  234. auto response = add_two_ints->downcast(std::move(event));
  235. std::cout << "Received sum response with value " << response.sum << std::endl;
  236. ...
  237. }
  238. ```