Skip to content

Commit 24df683

Browse files
pablogs9jamoralp
andauthored
Add configured examples with domain ID (#30)
* Add configured examples with domain ID * Allow ROS Domain ID to be configurable from CLI * Fix indentation Co-authored-by: Jose Antonio Moral <joseantoniomoralparras@gmail.com>
1 parent e4cc345 commit 24df683

2 files changed

Lines changed: 29 additions & 5 deletions

File tree

  • rclc/configuration_example

rclc/configuration_example/configured_publisher/main.c

Lines changed: 15 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,13 @@ void timer_callback(rcl_timer_t * timer, int64_t last_call_time)
2626
}
2727

2828
int main(int argc, char * const argv[])
29-
{
29+
{
30+
if (argc < 3 || argc > 4)
31+
{
32+
printf("Usage: configured_publisher <IP> <port> <DomainID (default: 0)>\n");
33+
return 1;
34+
}
35+
3036
rcl_allocator_t allocator = rcl_get_default_allocator();
3137
rclc_support_t support;
3238
rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
@@ -42,7 +48,11 @@ int main(int argc, char * const argv[])
4248

4349
// create node
4450
rcl_node_t node = rcl_get_zero_initialized_node();
45-
RCCHECK(rclc_node_init_default(&node, "int32_configured_publisher_rclc", "", &support));
51+
rcl_node_options_t node_ops = rcl_node_get_default_options();
52+
node_ops.domain_id = (size_t)(argc == 4 ? atoi(argv[3]) : 0);
53+
const char * node_name = "int32_configured_publisher_rclc";
54+
printf("Initializing node '%s' with ROS Domain ID %ld...\n",node_name, node_ops.domain_id);
55+
RCCHECK(rclc_node_init_with_options(&node, node_name, "", &support, &node_ops));
4656

4757
// create publisher
4858
RCCHECK(rclc_publisher_init_default(
@@ -69,9 +79,11 @@ int main(int argc, char * const argv[])
6979
RCCHECK(rclc_executor_add_timer(&executor, &timer));
7080

7181
msg.data = 0;
72-
82+
7383
rclc_executor_spin(&executor);
7484

7585
RCCHECK(rcl_publisher_fini(&publisher, &node));
7686
RCCHECK(rcl_node_fini(&node));
87+
88+
return 0;
7789
}

rclc/configuration_example/configured_subscriber/main.c

Lines changed: 14 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,12 @@ void subscription_callback(const void * msgin)
2323

2424
int main(int argc, const char * const * argv)
2525
{
26+
if (argc < 3 || argc > 4)
27+
{
28+
printf("Usage: configured_subscriber <IP> <port> <DomainID (default: 0)>\n");
29+
return 1;
30+
}
31+
2632
rcl_allocator_t allocator = rcl_get_default_allocator();
2733
rclc_support_t support;
2834
rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
@@ -38,7 +44,11 @@ int main(int argc, const char * const * argv)
3844

3945
// create node
4046
rcl_node_t node = rcl_get_zero_initialized_node();
41-
RCCHECK(rclc_node_init_default(&node, "int32_configured_subscriber_rclc", "", &support));
47+
rcl_node_options_t node_ops = rcl_node_get_default_options();
48+
node_ops.domain_id = (size_t)(argc == 4 ? atoi(argv[3]) : 0);
49+
const char * node_name = "int32_configured_subscriber_rclc";
50+
printf("Initializing node '%s' with ROS Domain ID %ld...\n", node_name, node_ops.domain_id);
51+
RCCHECK(rclc_node_init_with_options(&node, node_name, "", &support, &node_ops));
4252

4353
// create subscriber
4454
RCCHECK(rclc_subscription_init_default(
@@ -54,9 +64,11 @@ int main(int argc, const char * const * argv)
5464
unsigned int rcl_wait_timeout = 1000; // in ms
5565
RCCHECK(rclc_executor_set_timeout(&executor, RCL_MS_TO_NS(rcl_wait_timeout)));
5666
RCCHECK(rclc_executor_add_subscription(&executor, &subscriber, &msg, &subscription_callback, ON_NEW_DATA));
57-
67+
5868
rclc_executor_spin(&executor);
5969

6070
RCCHECK(rcl_subscription_fini(&subscriber, &node));
6171
RCCHECK(rcl_node_fini(&node));
72+
73+
return 0;
6274
}

0 commit comments

Comments
 (0)