From 0a7f13412e1954885f2b8f6af02c3871510628f7 Mon Sep 17 00:00:00 2001 From: "mergify[bot]" <37929162+mergify[bot]@users.noreply.github.com> Date: Wed, 22 Mar 2023 16:22:37 +0100 Subject: [PATCH] added documentation about number_of_handles in all examples. (#341) (#342) * added documentation about number_of_handles in all examples. Signed-off-by: Jan Staschulat * aligned prepare() and spin() in all functions Signed-off-by: Jan Staschulat * removed 'prepare' functions - to make it easier for beginners. Signed-off-by: Jan Staschulat --------- Signed-off-by: Jan Staschulat (cherry picked from commit 810afe1b84e0bc4ac397662694a1b27ae13d81b7) Co-authored-by: Jan Staschulat --- rclc_examples/src/example_action_client.c | 5 +++++ rclc_examples/src/example_action_server.c | 5 +++++ rclc_examples/src/example_client_node.c | 9 ++++++--- rclc_examples/src/example_executor.c | 7 ++++--- rclc_examples/src/example_executor_only_rcl.c | 8 ++++---- rclc_examples/src/example_executor_trigger.c | 8 ++++++-- rclc_examples/src/example_lifecycle_node.c | 5 +++++ rclc_examples/src/example_parameter_server.c | 9 ++++++--- rclc_examples/src/example_pingpong.cpp | 10 ++++++---- rclc_examples/src/example_service_node.c | 5 +++++ .../src/example_short_timer_long_subscription.c | 8 ++++++-- rclc_examples/src/example_sub_context.c | 5 +++++ 12 files changed, 63 insertions(+), 21 deletions(-) diff --git a/rclc_examples/src/example_action_client.c b/rclc_examples/src/example_action_client.c index e763bf67..e87a608e 100644 --- a/rclc_examples/src/example_action_client.c +++ b/rclc_examples/src/example_action_client.c @@ -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; diff --git a/rclc_examples/src/example_action_server.c b/rclc_examples/src/example_action_server.c index 6f5f2dbe..4595db0e 100644 --- a/rclc_examples/src/example_action_server.c +++ b/rclc_examples/src/example_action_server.c @@ -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); diff --git a/rclc_examples/src/example_client_node.c b/rclc_examples/src/example_client_node.c index 46a8242b..124fe7a7 100644 --- a/rclc_examples/src/example_client_node.c +++ b/rclc_examples/src/example_client_node.c @@ -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)); @@ -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)); diff --git a/rclc_examples/src/example_executor.c b/rclc_examples/src/example_executor.c index 5e3bd636..b9853ca2 100644 --- a/rclc_examples/src/example_executor.c +++ b/rclc_examples/src/example_executor.c @@ -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); @@ -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) diff --git a/rclc_examples/src/example_executor_only_rcl.c b/rclc_examples/src/example_executor_only_rcl.c index d37213b7..3d1c7cf3 100644 --- a/rclc_examples/src/example_executor_only_rcl.c +++ b/rclc_examples/src/example_executor_only_rcl.c @@ -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); @@ -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) diff --git a/rclc_examples/src/example_executor_trigger.c b/rclc_examples/src/example_executor_trigger.c index 235c3cac..8698bcb9 100644 --- a/rclc_examples/src/example_executor_trigger.c +++ b/rclc_examples/src/example_executor_trigger.c @@ -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); diff --git a/rclc_examples/src/example_lifecycle_node.c b/rclc_examples/src/example_lifecycle_node.c index c7a1b18a..abb6cab0 100644 --- a/rclc_examples/src/example_lifecycle_node.c +++ b/rclc_examples/src/example_lifecycle_node.c @@ -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, diff --git a/rclc_examples/src/example_parameter_server.c b/rclc_examples/src/example_parameter_server.c index 848cce35..24195f35 100644 --- a/rclc_examples/src/example_parameter_server.c +++ b/rclc_examples/src/example_parameter_server.c @@ -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, @@ -132,9 +137,7 @@ int main() rclc_parameter_get_int(¶m_server, "param2", ¶m2); rclc_parameter_get_double(¶m_server, "param3", ¶m3); - // Optional prepare for avoiding allocations during spin - rclc_executor_prepare(&executor); - + // Start Executor rclc_executor_spin(&executor); // clean up diff --git a/rclc_examples/src/example_pingpong.cpp b/rclc_examples/src/example_pingpong.cpp index f8b17ccf..0bba9932 100644 --- a/rclc_examples/src/example_pingpong.cpp +++ b/rclc_examples/src/example_pingpong.cpp @@ -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); @@ -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 )); diff --git a/rclc_examples/src/example_service_node.c b/rclc_examples/src/example_service_node.c index 4c5631db..faa487b2 100644 --- a/rclc_examples/src/example_service_node.c +++ b/rclc_examples/src/example_service_node.c @@ -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 diff --git a/rclc_examples/src/example_short_timer_long_subscription.c b/rclc_examples/src/example_short_timer_long_subscription.c index 6493e22f..1cefce47 100644 --- a/rclc_examples/src/example_short_timer_long_subscription.c +++ b/rclc_examples/src/example_short_timer_long_subscription.c @@ -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); @@ -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); diff --git a/rclc_examples/src/example_sub_context.c b/rclc_examples/src/example_sub_context.c index 33a3c5ae..86e1b22a 100644 --- a/rclc_examples/src/example_sub_context.c +++ b/rclc_examples/src/example_sub_context.c @@ -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);