@@ -39,18 +39,16 @@ int main(int argc, const char * const * argv)
3939 RCCHECK (rmw_uros_options_set_udp_address (argv [1 ], argv [2 ], rmw_options ))
4040 RCCHECK (rmw_uros_options_set_client_key (0xCAFEBABE , rmw_options ))
4141
42- size_t domain_id = (size_t )(argc == 4 ? atoi (argv [3 ]) : 0 );
43- const char * node_name = "int32_configured_subscriber_rclc" ;
44-
45- rcl_init_options_set_domain_id (& init_options , domain_id );
46- printf ("Initializing RCL '%s' with ROS Domain ID %ld...\n" , node_name , domain_id );
47-
4842 // create init_options
4943 RCCHECK (rclc_support_init_with_options (& support , 0 , NULL , & init_options , & allocator ));
5044
5145 // create node
5246 rcl_node_t node = rcl_get_zero_initialized_node ();
53- RCCHECK (rclc_node_init_default (& node , node_name , "" , & 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 ));
5452
5553 // create subscriber
5654 RCCHECK (rclc_subscription_init_default (
0 commit comments