Skip to content

Commit 720afd0

Browse files
JanStaschulatralph-lange
authored andcommitted
updated pub_sub and rclc_executor section.
Signed-off-by: Staschulat Jan <jan.staschulat@de.bosch.com>
1 parent e10a3be commit 720afd0

File tree

1 file changed

+131
-6
lines changed
  • _docs/tutorials/core/programming_rcl_rclc

1 file changed

+131
-6
lines changed

_docs/tutorials/core/programming_rcl_rclc/index.md

Lines changed: 131 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -35,17 +35,61 @@ if (rc != RCL_RET_OK) {
3535
}
3636
```
3737

38-
3938
## <a name="pub_sub"/>Publishers and Subscriptions
39+
Publisher and subscribers are created with the rclc-package with the following functions
40+
`rclc_publisher_init_default(..)` and `rclc_subscription_init_default(..)` in [rclc/publisher.h](https://github.com/micro-ROS/rclc/blob/master/rclc/include/rclc/publisher.h) and [rclc/node.h](https://github.com/micro-ROS/rclc/blob/master/rclc/include/rclc/subscription.h), respectively:
4041

4142

43+
```c
44+
// create publisher
45+
rcl_publisher_t my_pub;
46+
std_msgs__msg__String pub_msg;
47+
const char * topic_name = "topic_0";
48+
const rosidl_message_type_support_t * my_type_support =
49+
ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String);
50+
51+
rc = rclc_publisher_init_default(
52+
&my_pub,
53+
&my_node,
54+
my_type_support,
55+
topic_name);
56+
if (RCL_RET_OK != rc) {
57+
printf("Error in rclc_publisher_init_default %s.\n", topic_name);
58+
return -1;
59+
}
60+
// create publisher message
61+
std_msgs__msg__String__init(&pub_msg);
62+
const unsigned int PUB_MSG_SIZE = 20;
63+
char pub_string[PUB_MSG_SIZE];
64+
snprintf(pub_string, 13, "%s", "Hello World!");
65+
rosidl_generator_c__String__assignn(&pub_msg, pub_string, PUB_MSG_SIZE);
66+
67+
// create subscription
68+
rcl_subscription_t my_sub = rcl_get_zero_initialized_subscription();
69+
rc = rclc_subscription_init_default(
70+
&my_sub,
71+
&my_node,
72+
my_type_support,
73+
topic_name);
74+
if (rc != RCL_RET_OK) {
75+
printf("Failed to create subscriber %s.\n", topic_name);
76+
return -1;
77+
} else {
78+
printf("Created subscriber %s:\n", topic_name);
79+
}
80+
81+
// initialize string message for subscriber
82+
std_msgs__msg__String__init(&sub_msg);
83+
```
4284
4385
## <a name="services"/>Services
4486
4587
ROS 2 services is another communication mechanism between nodes. Services implement a client-server paradigm based on ROS 2 messages and types. Further information about ROS 2 services can be found [here](https://index.ros.org/doc/ros2/Tutorials/Services/Understanding-ROS2-Services/)
4688
4789
Ready to use code related to this tutorial can be found in [`micro-ROS-demos/rcl/addtwoints_server`](https://github.com/micro-ROS/micro-ROS-demos/blob/dashing/rcl/addtwoints_server/main.c) and [`micro-ROS-demos/rcl/addtwoints_client`](https://github.com/micro-ROS/micro-ROS-demos/blob/dashing/rcl/addtwoints_client/main.c) folders.
4890
91+
Note: Services are not supported in rclc package yet. Therefore the configuration is described using RCL layer.
92+
4993
Starting from a code where RCL is initialized and a micro-ROS node is created, these steps are required in order to generate a service server:
5094
5195
```c
@@ -90,7 +134,7 @@ Once service client and server are configured, service client can perform a requ
90134
91135
```c
92136
// Creating a service request
93-
int64_t seq;
137+
int64_t seq;
94138
example_interfaces__srv__AddTwoInts_Request req;
95139
req.a = 24;
96140
req.b = 42;
@@ -116,7 +160,7 @@ do {
116160
// Create a service response struct
117161
example_interfaces__srv__AddTwoInts_Response res;
118162
119-
// Take the response
163+
// Take the response
120164
rcl_ret_t rc = rcl_take_response(&client, &req_id, &res);
121165
122166
if (RCL_RET_OK == rc) {
@@ -132,7 +176,7 @@ On service server side, the ROS 2 node should be waiting for service requests an
132176
```c
133177
while(1){
134178
rcl_wait_set_clear(&wait_set);
135-
179+
136180
size_t index;
137181
rcl_wait_set_add_service(&wait_set, &service, &index);
138182

@@ -145,7 +189,7 @@ while(1){
145189
// Create a service request struct
146190
example_interfaces__srv__AddTwoInts_Request req;
147191

148-
// Take the request
192+
// Take the request
149193
rcl_take_request(&service, &req_id, &req);
150194

151195
printf("Service request value: %d + %d. Seq %d\n", (int)req.a, (int)req.b, (int)req_id.sequence_number);
@@ -161,7 +205,88 @@ while(1){
161205

162206

163207
## <a name="timers"/>Timers
164-
208+
A timer can be created with the rclc-package with the function
209+
`rclc_timer_init_default(..)` in [rclc/timer.h](https://github.com/micro-ROS/rclc/blob/master/rclc/include/rclc/timer.h):
210+
```c
211+
// create a timer, which will call the publisher with period=`timer_timeout` ms in the 'my_timer_callback'
212+
rcl_timer_t my_timer = rcl_get_zero_initialized_timer();
213+
const unsigned int timer_timeout = 1000;
214+
rc = rclc_timer_init_default(
215+
&my_timer,
216+
&support,
217+
RCL_MS_TO_NS(timer_timeout),
218+
my_timer_callback);
219+
if (rc != RCL_RET_OK) {
220+
printf("Error in rcl_timer_init_default.\n");
221+
return -1;
222+
} else {
223+
printf("Created timer with timeout %d ms.\n", timer_timeout);
224+
}
225+
```
165226
166227
## <a name="rclc_executor"/>Rclc Executor
228+
The Executor is configured and setup with the functions
229+
`rclc_executor_get_zero_initialized_executor(..)`, `rclc_executor_set_timeout(..)`, `rclc_executor_add_subscription(...)`, `rclc_executor_add_timer(...)`, `rclc_executor_spin_some(...)` and `rclc_executor_fini(...)` in [rclc/executor.h](https://github.com/micro-ROS/rclc/blob/master/rclc/include/rclc/executor.h).
230+
231+
Assuming that you have created a subscription and a timer, as described above, the following code snippet shows the configuration of the RCLC-executor.
232+
233+
The executor is configured with 2 handles, aka one subscription and one timer. The `support.context` is the ROS 2 context, as shown above with `rclc_support_init(...)`.
234+
235+
The timeout is the waiting time for new handles to get ready, for example new messages arrive or timers are ready. The unit of the timeout is milliseconds.
167236
237+
A subscription `my_sub`, a place-holder for it's message `sub_msg` and it's corresponding callback `my_subscriber_callback` is added to the executor with the function `rclc_executor_add_subscription(...)`
238+
239+
A timers is added to the executor with the function `rclc_executor_add_timer(...)`
240+
241+
A key feature of the rclc-Executor is, that the order of these functions to add handles matters. It defines the processing order when multiple messages have arrived or timers are ready. This provides full control over the execution order to the user.
242+
243+
There are are several functions, how to start the executor, one is `rclc_executor_spin_some(...)`, which allows the user to specify a timeout in nanoseconds.
244+
245+
Finally the code snippet shows how to destroy the objects for the node, publisher, subscriber and the executor with the respective fini-methods.
246+
247+
```c
248+
rclc_executor_t executor;
249+
250+
// compute total number of subsribers and timers
251+
unsigned int num_handles = 1 + 1;
252+
printf("Debug: number of DDS handles: %u\n", num_handles);
253+
executor = rclc_executor_get_zero_initialized_executor();
254+
rclc_executor_init(&executor, &support.context, num_handles, &allocator);
255+
256+
// set timeout for rcl_wait()
257+
unsigned int rcl_wait_timeout = 1000; // in ms
258+
rc = rclc_executor_set_timeout(&executor, RCL_MS_TO_NS(rcl_wait_timeout));
259+
if (rc != RCL_RET_OK) {
260+
printf("Error in rclc_executor_set_timeout.");
261+
}
262+
263+
// add subscription to executor
264+
rc = rclc_executor_add_subscription(&executor, &my_sub, &sub_msg, &my_subscriber_callback,
265+
ON_NEW_DATA);
266+
if (rc != RCL_RET_OK) {
267+
printf("Error in rclc_executor_add_subscription. \n");
268+
}
269+
270+
rclc_executor_add_timer(&executor, &my_timer);
271+
if (rc != RCL_RET_OK) {
272+
printf("Error in rclc_executor_add_timer.\n");
273+
}
274+
275+
for (;;) {
276+
// timeout specified in ns (here 1s)
277+
rclc_executor_spin_some(&executor, 1000 * (1000 * 1000));
278+
}
279+
280+
// clean up
281+
rc = rclc_executor_fini(&executor);
282+
rc += rcl_publisher_fini(&my_pub, &my_node);
283+
rc += rcl_timer_fini(&my_timer);
284+
rc += rcl_subscription_fini(&my_sub, &my_node);
285+
rc += rcl_node_fini(&my_node);
286+
rc += rclc_support_fini(&support);
287+
288+
if (rc != RCL_RET_OK) {
289+
printf("Error while cleaning up!\n");
290+
return -1;
291+
}
292+
```

0 commit comments

Comments
 (0)