Skip to content

Commit

Permalink
Merge branch 'humble' of https://github.com/ros2/rclc into humble
Browse files Browse the repository at this point in the history
  • Loading branch information
JanStaschulat committed Mar 22, 2023
2 parents 2287f3e + 0a7f134 commit 25b8970
Show file tree
Hide file tree
Showing 12 changed files with 63 additions and 21 deletions.
5 changes: 5 additions & 0 deletions rclc_examples/src/example_action_client.c
Original file line number Diff line number Diff line change
Expand Up @@ -154,6 +154,11 @@ int main()

// Create executor
rclc_executor_t executor;
// Note:
// If you need more than the default number of publisher/subscribers, etc., you
// need to configure the micro-ROS middleware also!
// See documentation in the executor.h at the function rclc_executor_init()
// for more details.
rclc_executor_init(&executor, &support.context, 1, &allocator);

example_interfaces__action__Fibonacci_FeedbackMessage ros_feedback;
Expand Down
5 changes: 5 additions & 0 deletions rclc_examples/src/example_action_server.c
Original file line number Diff line number Diff line change
Expand Up @@ -139,6 +139,11 @@ int main()
);

// Create executor
// Note:
// If you need more than the default number of publisher/subscribers, etc., you
// need to configure the micro-ROS middleware also!
// See documentation in the executor.h at the function rclc_executor_init()
// for more details.
rclc_executor_t executor;
rclc_executor_init(&executor, &support.context, 1, &allocator);

Expand Down
9 changes: 6 additions & 3 deletions rclc_examples/src/example_client_node.c
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,11 @@ int main(int argc, const char * const * argv)
ROSIDL_GET_SRV_TYPE_SUPPORT(example_interfaces, srv, AddTwoInts), "/addtwoints"));

// create executor
// Note:
// If you need more than the default number of publisher/subscribers, etc., you
// need to configure the micro-ROS middleware also!
// See documentation in the executor.h at the function rclc_executor_init()
// for more details.
rclc_executor_t executor = rclc_executor_get_zero_initialized_executor();
RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator));

Expand All @@ -75,9 +80,7 @@ int main(int argc, const char * const * argv)
RCCHECK(rcl_send_request(&client, &req, &seq))
printf("Send service request %ld + %ld.\n", req.a, req.b);

// Optional prepare for avoiding allocations during spin
rclc_executor_prepare(&executor);

// Start Executor
rclc_executor_spin(&executor);

RCCHECK(rcl_client_fini(&client, &node));
Expand Down
7 changes: 4 additions & 3 deletions rclc_examples/src/example_executor.c
Original file line number Diff line number Diff line change
Expand Up @@ -139,10 +139,10 @@ int main(int argc, const char * argv[])
// total number of handles = #subscriptions + #timers
//
// Note:
// If you need more than the default number of publisher/subscribers, etc., you
// If you need more than the default number of publisher/subscribers, etc., you
// need to configure the micro-ROS middleware also!
// See documentation in the executor.h at the function rclc_executor_init()
// for more details.
// See documentation in the executor.h at the function rclc_executor_init()
// for more details.
unsigned int num_handles = 1 + 1;
printf("Debug: number of DDS handles: %u\n", num_handles);
rclc_executor_init(&executor, &support.context, num_handles, &allocator);
Expand All @@ -160,6 +160,7 @@ int main(int argc, const char * argv[])
printf("Error in rclc_executor_add_timer.\n");
}

// Start Executor
rclc_executor_spin(&executor);

// clean up (never called in this example)
Expand Down
8 changes: 4 additions & 4 deletions rclc_examples/src/example_executor_only_rcl.c
Original file line number Diff line number Diff line change
Expand Up @@ -160,10 +160,10 @@ int main(int argc, const char * argv[])
rclc_executor_t executor;

// Note:
// If you need more than the default number of publisher/subscribers, etc., you
// If you need more than the default number of publisher/subscribers, etc., you
// need to configure the micro-ROS middleware also!
// See documentation in the executor.h at the function rclc_executor_init()
// for more details.
// See documentation in the executor.h at the function rclc_executor_init()
// for more details.
unsigned int num_handles = 1 + 1;
printf("Debug: number of DDS handles: %u\n", num_handles);
rclc_executor_init(&executor, &context, num_handles, &allocator);
Expand All @@ -187,7 +187,7 @@ int main(int argc, const char * argv[])
if (rc != RCL_RET_OK) {
printf("Error in rclc_executor_add_timer.\n");
}

// Start Executor
rclc_executor_spin(&executor);

// clean up (never reached)
Expand Down
8 changes: 6 additions & 2 deletions rclc_examples/src/example_executor_trigger.c
Original file line number Diff line number Diff line change
Expand Up @@ -317,8 +317,12 @@ int main(int argc, const char * argv[])
rclc_executor_t executor_pub;
rclc_executor_t executor_sub;


// Executor for publishing messages
// Executor
// Note:
// If you need more than the default number of publisher/subscribers, etc., you
// need to configure the micro-ROS middleware also!
// See documentation in the executor.h at the function rclc_executor_init()
// for more details.
unsigned int num_handles_pub = 2;
printf("Executor_pub: number of DDS handles: %u\n", num_handles_pub);
rclc_executor_init(&executor_pub, &support.context, num_handles_pub, &allocator);
Expand Down
5 changes: 5 additions & 0 deletions rclc_examples/src/example_lifecycle_node.c
Original file line number Diff line number Diff line change
Expand Up @@ -96,6 +96,11 @@ int main(int argc, const char * argv[])
}

// Executor
// Note:
// If you need more than the default number of publisher/subscribers, etc., you
// need to configure the micro-ROS middleware also!
// See documentation in the executor.h at the function rclc_executor_init()
// for more details.
rclc_executor_t executor;
RCCHECK(rclc_executor_init(
&executor,
Expand Down
9 changes: 6 additions & 3 deletions rclc_examples/src/example_parameter_server.c
Original file line number Diff line number Diff line change
Expand Up @@ -101,6 +101,11 @@ int main()
timer_callback);

// Create executor
// Note:
// If you need more than the default number of publisher/subscribers, etc., you
// need to configure the micro-ROS middleware also!
// See documentation in the executor.h at the function rclc_executor_init()
// for more details.
rclc_executor_t executor;
rclc_executor_init(
&executor, &support.context, RCLC_EXECUTOR_PARAMETER_SERVER_HANDLES + 1,
Expand Down Expand Up @@ -132,9 +137,7 @@ int main()
rclc_parameter_get_int(&param_server, "param2", &param2);
rclc_parameter_get_double(&param_server, "param3", &param3);

// Optional prepare for avoiding allocations during spin
rclc_executor_prepare(&executor);

// Start Executor
rclc_executor_spin(&executor);

// clean up
Expand Down
10 changes: 6 additions & 4 deletions rclc_examples/src/example_pingpong.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -366,6 +366,11 @@ int main(int argc, const char * argv[])
rclc_executor_t ping_executor;
ping_executor = rclc_executor_get_zero_initialized_executor();
// total number of handles = #subscriptions + #timers + #Services (in below case services are 0)
// Note:
// If you need more than the default number of publisher/subscribers, etc., you
// need to configure the micro-ROS middleware also!
// See documentation in the executor.h at the function rclc_executor_init()
// for more details.
unsigned int pingNode_num_handles = 1 + 1;
printf("Debug: number of DDS handles: %u\n", pingNode_num_handles);
rclc_executor_init(&ping_executor, &support.context, pingNode_num_handles, &allocator);
Expand Down Expand Up @@ -412,13 +417,10 @@ int main(int argc, const char * argv[])
printf("Error in rclc_executor_add_timer.\n");
}


// Optional prepare for avoiding allocations during spin
// Optional: prepare for avoiding allocations during spin
rclc_executor_prepare(&ping_executor);
rclc_executor_prepare(&pong_executor);

// rclc_executor_spin(&executor ); end less loop

for (unsigned int i = 0; i < 10; i++) {
// timeout specified in nanoseconds (here 1s)
rclc_executor_spin_some(&ping_executor, RCL_MS_TO_NS( 1000 ));
Expand Down
5 changes: 5 additions & 0 deletions rclc_examples/src/example_service_node.c
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,11 @@ int main(int argc, const char * const * argv)

// create executor
rclc_executor_t executor = rclc_executor_get_zero_initialized_executor();
// Note:
// If you need more than the default number of publisher/subscribers, etc., you
// need to configure the micro-ROS middleware also!
// See documentation in the executor.h at the function rclc_executor_init()
// for more details.
RCCHECK(rclc_executor_init(&executor, &support.context, 1, &allocator));

unsigned int rcl_wait_timeout = 1000; // in ms
Expand Down
8 changes: 6 additions & 2 deletions rclc_examples/src/example_short_timer_long_subscription.c
Original file line number Diff line number Diff line change
Expand Up @@ -162,6 +162,11 @@ int main(int argc, const char * argv[])
// total number of handles = #subscriptions + #timers
// check also xrce-dds configuration for maximum number of publisher,
// subscribers, timers etc.
// Note:
// If you need more than the default number of publisher/subscribers, etc., you
// need to configure the micro-ROS middleware also!
// See documentation in the executor.h at the function rclc_executor_init()
// for more details.
unsigned int num_handles = 1 + 2;
printf("Debug: number of DDS handles: %u\n", num_handles);
rclc_executor_init(&executor, &support.context, num_handles, &allocator);
Expand All @@ -183,10 +188,9 @@ int main(int argc, const char * argv[])
if (rc != RCL_RET_OK) {
printf("Error in rclc_executor_add_timer.\n");
}

// Start Executor
rclc_executor_spin(&executor);


// clean up
rc = rclc_executor_fini(&executor);
rc += rcl_publisher_fini(&my_pub, &my_node);
Expand Down
5 changes: 5 additions & 0 deletions rclc_examples/src/example_sub_context.c
Original file line number Diff line number Diff line change
Expand Up @@ -142,6 +142,11 @@ int main(int argc, const char * argv[])
rclc_executor_t executor;
executor = rclc_executor_get_zero_initialized_executor();
// total number of handles = #subscriptions + #timers
// Note:
// If you need more than the default number of publisher/subscribers, etc., you
// need to configure the micro-ROS middleware also!
// See documentation in the executor.h at the function rclc_executor_init()
// for more details.
unsigned int num_handles = n_topics + 0;
printf("Debug: number of DDS handles: %u\n", num_handles);
rclc_executor_init(&executor, &support.context, num_handles, &allocator);
Expand Down

0 comments on commit 25b8970

Please sign in to comment.