1414example_interfaces__srv__AddTwoInts_Request req ;
1515example_interfaces__srv__AddTwoInts_Response res ;
1616
17- void service_callback (const void * req , rmw_request_id_t * req_id , void * res ){
17+ void service_callback (const void * req , void * res ){
1818 example_interfaces__srv__AddTwoInts_Request * req_in = (example_interfaces__srv__AddTwoInts_Request * ) req ;
1919 example_interfaces__srv__AddTwoInts_Response * res_in = (example_interfaces__srv__AddTwoInts_Response * ) res ;
2020
21- printf ("Service request value: %d + %d. Seq %d \n" , (int ) req_in -> a , (int ) req_in -> b , ( int ) req_id -> sequence_number );
21+ printf ("Service request value: %d + %d.\n" , (int ) req_in -> a , (int ) req_in -> b );
2222
2323 res_in -> sum = req_in -> a + req_in -> b ;
2424}
2525
26-
2726int main (int argc , const char * const * argv )
2827{
2928 RCLC_UNUSED (argc );
@@ -35,15 +34,15 @@ int main(int argc, const char * const * argv)
3534 RCCHECK (rclc_support_init (& support , 0 , NULL , & allocator ));
3635
3736 // create node
38- rcl_node_t node = rcl_get_zero_initialized_node () ;
37+ rcl_node_t node ;
3938 RCCHECK (rclc_node_init_default (& node , "add_twoints_client_rclc" , "" , & support ));
4039
4140 // create service
42- rcl_service_t service = rcl_get_zero_initialized_service () ;
41+ rcl_service_t service ;
4342 RCCHECK (rclc_service_init_default (& service , & node , ROSIDL_GET_SRV_TYPE_SUPPORT (example_interfaces , srv , AddTwoInts ), "/addtwoints" ));
4443
4544 // create executor
46- rclc_executor_t executor = rclc_executor_get_zero_initialized_executor () ;
45+ rclc_executor_t executor ;
4746 RCCHECK (rclc_executor_init (& executor , & support .context , 1 , & allocator ));
4847
4948 unsigned int rcl_wait_timeout = 10 ; // in ms
0 commit comments