diff --git a/rcl/include/rcl/client.h b/rcl/include/rcl/client.h index 56dc09a90..c205c36dc 100644 --- a/rcl/include/rcl/client.h +++ b/rcl/include/rcl/client.h @@ -72,7 +72,8 @@ rcl_get_zero_initialized_client(void); * required rosidl_service_type_support_t object. * This object can be obtained using a language appropriate mechanism. * \todo TODO(wjwwood) write these instructions once and link to it instead - * For C a macro can be used (for example `example_interfaces/AddTwoInts`): + * + * For C, a macro can be used (for example `example_interfaces/AddTwoInts`): * * ```c * #include @@ -82,7 +83,7 @@ rcl_get_zero_initialized_client(void); * ROSIDL_GET_SRV_TYPE_SUPPORT(example_interfaces, AddTwoInts); * ``` * - * For C++ a template function is used: + * For C++, a template function is used: * * ```cpp * #include diff --git a/rcl/include/rcl/publisher.h b/rcl/include/rcl/publisher.h index 3aadd1e36..d91183f1a 100644 --- a/rcl/include/rcl/publisher.h +++ b/rcl/include/rcl/publisher.h @@ -68,7 +68,8 @@ rcl_get_zero_initialized_publisher(void); * required rosidl_message_type_support_t object. * This object can be obtained using a language appropriate mechanism. * \todo TODO(wjwwood) write these instructions once and link to it instead - * For C a macro can be used (for example `std_msgs/String`): + * + * For C, a macro can be used (for example `std_msgs/String`): * * ```c * #include @@ -77,7 +78,7 @@ rcl_get_zero_initialized_publisher(void); * ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String); * ``` * - * For C++ a template function is used: + * For C++, a template function is used: * * ```cpp * #include diff --git a/rcl/include/rcl/rcl.h b/rcl/include/rcl/rcl.h index 66ba0de6e..0405b9ba6 100644 --- a/rcl/include/rcl/rcl.h +++ b/rcl/include/rcl/rcl.h @@ -51,7 +51,7 @@ * * Further still there are some useful abstractions and utilities: * - * - Allocator concept, which can used to control allocation in `rcl_*` functions + * - Allocator concept, which can be used to control allocation in `rcl_*` functions * - rcl/allocator.h * - Concept of ROS Time and access to steady and system wall time * - rcl/time.h diff --git a/rcl/include/rcl/service.h b/rcl/include/rcl/service.h index 4f36bd494..b76039268 100644 --- a/rcl/include/rcl/service.h +++ b/rcl/include/rcl/service.h @@ -69,7 +69,8 @@ rcl_get_zero_initialized_service(void); * required rosidl_service_type_support_t object. * This object can be obtained using a language appropriate mechanism. * \todo TODO(wjwwood) write these instructions once and link to it instead - * For C a macro can be used (for example `example_interfaces/AddTwoInts`): + * + * For C, a macro can be used (for example `example_interfaces/AddTwoInts`): * * ```c * #include @@ -78,7 +79,7 @@ rcl_get_zero_initialized_service(void); * ROSIDL_GET_SRV_TYPE_SUPPORT(example_interfaces, AddTwoInts); * ``` * - * For C++ a template function is used: + * For C++, a template function is used: * * ```cpp * #include @@ -263,7 +264,7 @@ rcl_take_request( * owned by the calling code, but should remain constant during * rcl_send_response(). * - e This function is thread safe so long as access to both the service and the + * This function is thread safe so long as access to both the service and the * `ros_response` is synchronized. * That means that calling rcl_send_response() from multiple threads is * allowed, but calling rcl_send_response() at the same time as non-thread safe diff --git a/rcl/include/rcl/wait.h b/rcl/include/rcl/wait.h index 5eed64f4c..05265d591 100644 --- a/rcl/include/rcl/wait.h +++ b/rcl/include/rcl/wait.h @@ -265,10 +265,10 @@ rcl_wait_set_clear(rcl_wait_set_t * wait_set); * * \param[inout] wait_set struct to be resized * \param[in] subscriptions_size a size for the new subscriptions set - * \param[in] guard_conditions_size a size for the new subscriptions set - * \param[in] timers_size a size for the new subscriptions set - * \param[in] clients_size a size for the new subscriptions set - * \param[in] services_size a size for the new subscriptions set + * \param[in] guard_conditions_size a size for the new guard conditions set + * \param[in] timers_size a size for the new timers set + * \param[in] clients_size a size for the new clients set + * \param[in] services_size a size for the new services set * \return `RCL_RET_OK` if resized successfully, or * \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or * \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or @@ -321,7 +321,7 @@ rcl_wait_set_add_client( rcl_wait_set_t * wait_set, const rcl_client_t * client); -/// Store a pointer to the client in the next empty spot in the set. +/// Store a pointer to the service in the next empty spot in the set. /** * This function behaves exactly the same as for subscriptions. * \see rcl_wait_set_add_subscription