Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
18 changes: 15 additions & 3 deletions rclc/configuration_example/configured_publisher/main.c
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,13 @@ void timer_callback(rcl_timer_t * timer, int64_t last_call_time)
}

int main(int argc, char * const argv[])
{
{
if (argc < 3 || argc > 4)
{
printf("Usage: configured_publisher <IP> <port> <DomainID (default: 0)>\n");
return 1;
}

rcl_allocator_t allocator = rcl_get_default_allocator();
rclc_support_t support;
rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
Expand All @@ -42,7 +48,11 @@ int main(int argc, char * const argv[])

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

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

msg.data = 0;

rclc_executor_spin(&executor);

RCCHECK(rcl_publisher_fini(&publisher, &node));
RCCHECK(rcl_node_fini(&node));

return 0;
}
16 changes: 14 additions & 2 deletions rclc/configuration_example/configured_subscriber/main.c
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,12 @@ void subscription_callback(const void * msgin)

int main(int argc, const char * const * argv)
{
if (argc < 3 || argc > 4)
{
printf("Usage: configured_subscriber <IP> <port> <DomainID (default: 0)>\n");
return 1;
}

rcl_allocator_t allocator = rcl_get_default_allocator();
rclc_support_t support;
rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
Expand All @@ -38,7 +44,11 @@ int main(int argc, const char * const * argv)

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

// create subscriber
RCCHECK(rclc_subscription_init_default(
Expand All @@ -54,9 +64,11 @@ int main(int argc, const char * const * argv)
unsigned int rcl_wait_timeout = 1000; // in ms
RCCHECK(rclc_executor_set_timeout(&executor, RCL_MS_TO_NS(rcl_wait_timeout)));
RCCHECK(rclc_executor_add_subscription(&executor, &subscriber, &msg, &subscription_callback, ON_NEW_DATA));

rclc_executor_spin(&executor);

RCCHECK(rcl_subscription_fini(&subscriber, &node));
RCCHECK(rcl_node_fini(&node));

return 0;
}