From 54741045936151f6c291a56542c90e701d781a33 Mon Sep 17 00:00:00 2001 From: Tomoya Fujita Date: Wed, 8 Mar 2023 18:27:21 -0800 Subject: [PATCH] doc update, ROS message accessibility depends on RMW implementation. Signed-off-by: Tomoya Fujita --- rcl/include/rcl/client.h | 6 ++--- rcl/include/rcl/publisher.h | 6 ++--- rcl/include/rcl/service.h | 6 ++--- rcl_action/include/rcl_action/action_client.h | 24 +++++++++---------- 4 files changed, 21 insertions(+), 21 deletions(-) diff --git a/rcl/include/rcl/client.h b/rcl/include/rcl/client.h index f7995fabc..e3a447a77 100644 --- a/rcl/include/rcl/client.h +++ b/rcl/include/rcl/client.h @@ -227,9 +227,9 @@ rcl_client_get_default_options(void); * but calling rcl_send_request() at the same time as non-thread safe client * functions is not, e.g. calling rcl_send_request() and rcl_client_fini() * concurrently is not allowed. - * Before calling rcl_send_request() the message can change and after calling - * rcl_send_request() the message can change, but it cannot be changed during - * the `send_request` call. + * The message cannot change during the rcl_send_request() call. + * Before calling rcl_send_request() the message can change but after calling + * rcl_send_request() it depends on RMW implementation behavior. * The same `ros_request`, however, can be passed to multiple calls of * rcl_send_request() simultaneously, even if the clients differ. * The `ros_request` is unmodified by rcl_send_request(). diff --git a/rcl/include/rcl/publisher.h b/rcl/include/rcl/publisher.h index 8736c78c0..51aa7421e 100644 --- a/rcl/include/rcl/publisher.h +++ b/rcl/include/rcl/publisher.h @@ -300,9 +300,9 @@ rcl_return_loaned_message_from_publisher( * calling rcl_publish() at the same time as non-thread safe publisher * functions is not, e.g. calling rcl_publish() and rcl_publisher_fini() * concurrently is not allowed. - * Before calling rcl_publish() the message can change and after calling - * rcl_publish() the message can change, but it cannot be changed during the - * publish call. + * The message cannot change during the rcl_publish() call. + * Before calling rcl_publish() the message can change but after calling + * rcl_publish() it depends on RMW implementation behavior. * The same `ros_message`, however, can be passed to multiple calls of * rcl_publish() simultaneously, even if the publishers differ. * The `ros_message` is unmodified by rcl_publish(). diff --git a/rcl/include/rcl/service.h b/rcl/include/rcl/service.h index dec7dc913..56e26459c 100644 --- a/rcl/include/rcl/service.h +++ b/rcl/include/rcl/service.h @@ -308,9 +308,9 @@ rcl_take_request( * allowed, but calling rcl_send_response() at the same time as non-thread safe * service functions is not, e.g. calling rcl_send_response() and * rcl_service_fini() concurrently is not allowed. - * Before calling rcl_send_response() the message can change and after calling - * rcl_send_response() the message can change, but it cannot be changed during - * the rcl_send_response() call. + * The message cannot change during the rcl_send_response() call. + * Before calling rcl_send_response() the message can change but after calling + * rcl_send_response() it depends on RMW implementation behavior. * The same `ros_response`, however, can be passed to multiple calls of * rcl_send_response() simultaneously, even if the services differ. * The `ros_response` is unmodified by rcl_send_response(). diff --git a/rcl_action/include/rcl_action/action_client.h b/rcl_action/include/rcl_action/action_client.h index b686b65f1..e49966c4d 100644 --- a/rcl_action/include/rcl_action/action_client.h +++ b/rcl_action/include/rcl_action/action_client.h @@ -291,9 +291,9 @@ rcl_action_server_is_available( * * The ROS goal message given by the `ros_goal_request` void pointer is always * owned by the calling code, but should remain constant during execution of this - * function. i.e. Before and after calling rcl_action_send_goal_request() the - * `ros_goal_request` message can change, but it cannot be changed during the call to - * rcl_action_send_goal_request(). + * function. i.e. The message cannot change during the rcl_action_send_goal_request() call. + * Before calling rcl_action_send_goal_request() the message can change but after calling + * rcl_action_send_goal_request() it depends on RMW implementation behavior. * The same `ros_goal_request` can be passed to multiple calls of this function * simultaneously, even if the action clients differ. * @@ -346,9 +346,9 @@ rcl_action_send_goal_request( * If the take is successful, this function will populate the fields of `ros_goal_response`. * The ROS message given by the `ros_goal_response` void pointer is always * owned by the calling code, but should remain constant during execution of this - * function. i.e. Before and after calling rcl_action_send_goal_response() the - * `ros_goal_response` message can change, but it cannot be changed during the call to - * rcl_action_send_goal_response(). + * function. i.e. The message cannot change during the rcl_action_send_goal_response() call. + * Before calling rcl_action_send_goal_response() the message can change but after calling + * rcl_action_send_goal_response() it depends on RMW implementation behavior. * *
* Attribute | Adherence @@ -481,9 +481,9 @@ rcl_action_take_status( * * The ROS message given by the `ros_result_request` void pointer is always * owned by the calling code, but should remain constant during execution of this - * function. i.e. Before and after calling rcl_action_send_result_request() the - * `ros_result_request` message can change, but it cannot be changed during the call to - * rcl_action_send_result_request(). + * function. i.e. The message cannot change during the rcl_action_send_result_request() call. + * Before calling rcl_action_send_result_request() the message can change but after calling + * rcl_action_send_result_request() it depends on RMW implementation behavior. * The same `ros_result_request` can be passed to multiple calls of this function * simultaneously, even if the action clients differ. * @@ -536,9 +536,9 @@ rcl_action_send_result_request( * If the take is successful, this function will populate the fields of `ros_result_response`. * The ROS message given by the `ros_result_response` void pointer is always * owned by the calling code, but should remain constant during execution of this - * function. i.e. Before and after calling rcl_action_take_result_response() the - * `ros_result_response` message can change, but it cannot be changed during the call to - * rcl_action_take_result_response(). + * function. i.e. The message cannot change during the rcl_action_take_result_response() call. + * Before calling rcl_action_take_result_response() the message can change but after calling + * rcl_action_take_result_response() it depends on RMW implementation behavior. * * If allocation is required when taking the result, e.g. if space needs to * be allocated for a dynamically sized array in the target message, then the