Skip to content

Commit e90cdc5

Browse files
committed
Fix indentation
Fix indentation
1 parent c5d19b3 commit e90cdc5

2 files changed

Lines changed: 27 additions & 27 deletions

File tree

rclc/addtwoints_client/main.c

Lines changed: 15 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -21,28 +21,28 @@ void client_callback(const void * msg, rmw_request_id_t * req_id){
2121

2222
int main(int argc, const char * const * argv)
2323
{
24-
RCLC_UNUSED(argc);
25-
RCLC_UNUSED(argv);
24+
RCLC_UNUSED(argc);
25+
RCLC_UNUSED(argv);
2626
rcl_allocator_t allocator = rcl_get_default_allocator();
27-
rclc_support_t support;
27+
rclc_support_t support;
2828

29-
// create init_options
30-
RCCHECK(rclc_support_init(&support, 0, NULL, &allocator));
29+
// create init_options
30+
RCCHECK(rclc_support_init(&support, 0, NULL, &allocator));
3131

32-
// create node
33-
rcl_node_t node = rcl_get_zero_initialized_node();
34-
RCCHECK(rclc_node_init_default(&node, "add_twoints_client_rclc", "", &support));
32+
// create node
33+
rcl_node_t node = rcl_get_zero_initialized_node();
34+
RCCHECK(rclc_node_init_default(&node, "add_twoints_client_rclc", "", &support));
3535

3636
// create client
3737
rcl_client_t client = rcl_get_zero_initialized_client();
3838
RCCHECK(rclc_client_init_default(&client, &node, ROSIDL_GET_SRV_TYPE_SUPPORT(example_interfaces, srv, AddTwoInts), "/addtwoints"));
3939

4040
// create executor
41-
rclc_executor_t executor = rclc_executor_get_zero_initialized_executor();
42-
RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator));
41+
rclc_executor_t executor = rclc_executor_get_zero_initialized_executor();
42+
RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator));
4343

44-
unsigned int rcl_wait_timeout = 10; // in ms
45-
RCCHECK(rclc_executor_set_timeout(&executor, RCL_MS_TO_NS(rcl_wait_timeout)));
44+
unsigned int rcl_wait_timeout = 10; // in ms
45+
RCCHECK(rclc_executor_set_timeout(&executor, RCL_MS_TO_NS(rcl_wait_timeout)));
4646
RCCHECK(rclc_executor_add_client(&executor, &client, &res, client_callback));
4747

4848
int64_t seq;
@@ -54,9 +54,9 @@ int main(int argc, const char * const * argv)
5454

5555
RCCHECK(rcl_send_request(&client, &req, &seq))
5656
printf("Send service request %ld + %ld. Seq %ld\n",req.a, req.b, seq);
57-
57+
5858
rclc_executor_spin(&executor);
5959

60-
RCCHECK(rcl_client_fini(&client, &node));
61-
RCCHECK(rcl_node_fini(&node));
60+
RCCHECK(rcl_client_fini(&client, &node));
61+
RCCHECK(rcl_node_fini(&node));
6262
}

rclc/addtwoints_server/main.c

Lines changed: 12 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -29,30 +29,30 @@ int main(int argc, const char * const * argv)
2929
RCLC_UNUSED(argc);
3030
RCLC_UNUSED(argv);
3131
rcl_allocator_t allocator = rcl_get_default_allocator();
32-
rclc_support_t support;
32+
rclc_support_t support;
3333

34-
// create init_options
35-
RCCHECK(rclc_support_init(&support, 0, NULL, &allocator));
34+
// create init_options
35+
RCCHECK(rclc_support_init(&support, 0, NULL, &allocator));
3636

37-
// create node
38-
rcl_node_t node = rcl_get_zero_initialized_node();
39-
RCCHECK(rclc_node_init_default(&node, "add_twoints_client_rclc", "", &support));
37+
// create node
38+
rcl_node_t node = rcl_get_zero_initialized_node();
39+
RCCHECK(rclc_node_init_default(&node, "add_twoints_client_rclc", "", &support));
4040

4141
// create service
4242
rcl_service_t service = rcl_get_zero_initialized_service();
4343
RCCHECK(rclc_service_init_default(&service, &node, ROSIDL_GET_SRV_TYPE_SUPPORT(example_interfaces, srv, AddTwoInts), "/addtwoints"));
4444

4545
// create executor
46-
rclc_executor_t executor = rclc_executor_get_zero_initialized_executor();
47-
RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator));
46+
rclc_executor_t executor = rclc_executor_get_zero_initialized_executor();
47+
RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator));
4848

49-
unsigned int rcl_wait_timeout = 10; // in ms
50-
RCCHECK(rclc_executor_set_timeout(&executor, RCL_MS_TO_NS(rcl_wait_timeout)));
49+
unsigned int rcl_wait_timeout = 10; // in ms
50+
RCCHECK(rclc_executor_set_timeout(&executor, RCL_MS_TO_NS(rcl_wait_timeout)));
5151

5252
RCCHECK(rclc_executor_add_service(&executor, &service, &req, &res, service_callback));
5353

5454
rclc_executor_spin(&executor);
5555

56-
RCCHECK(rcl_service_fini(&service, &node));
57-
RCCHECK(rcl_node_fini(&node));
56+
RCCHECK(rcl_service_fini(&service, &node));
57+
RCCHECK(rcl_node_fini(&node));
5858
}

0 commit comments

Comments
 (0)