diff --git a/rclcpp/include/rclcpp/clock.hpp b/rclcpp/include/rclcpp/clock.hpp index 211966e..45604cf 100644 --- a/rclcpp/include/rclcpp/clock.hpp +++ b/rclcpp/include/rclcpp/clock.hpp @@ -115,9 +115,9 @@ public: * * Function is only applicable if the clock_type is `RCL_ROS_TIME` * - * \param pre_callback. Must be non-throwing - * \param post_callback. Must be non-throwing. - * \param threshold. Callbacks will be triggered if the time jump is greater + * \param pre_callback Must be non-throwing + * \param post_callback Must be non-throwing. + * \param threshold Callbacks will be triggered if the time jump is greater * then the threshold. * \throws anything rclcpp::exceptions::throw_from_rcl_error can throw. * \throws std::bad_alloc if the allocation of the JumpHandler fails. diff --git a/rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp b/rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp index 062b6fb..c18df5b 100644 --- a/rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp +++ b/rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp @@ -49,6 +49,7 @@ public: * \param number_of_threads number of threads to have in the thread pool, * the default 0 will use the number of cpu cores found instead * \param yield_before_execute if true std::this_thread::yield() is called + * \param timeout maximum time to wait */ RCLCPP_PUBLIC MultiThreadedExecutor( diff --git a/rclcpp/include/rclcpp/node.hpp b/rclcpp/include/rclcpp/node.hpp index f379367..7706fa8 100644 --- a/rclcpp/include/rclcpp/node.hpp +++ b/rclcpp/include/rclcpp/node.hpp @@ -235,7 +235,7 @@ public: /// Create and return a Client. /** * \param[in] service_name The topic to service on. - * \param[in] rmw_qos_profile_t Quality of service profile for client. + * \param[in] qos_profile rmw_qos_profile_t Quality of service profile for client. * \param[in] group Callback group to call the service. * \return Shared pointer to the created client. */ @@ -250,7 +250,7 @@ public: /** * \param[in] service_name The topic to service on. * \param[in] callback User-defined callback function. - * \param[in] rmw_qos_profile_t Quality of service profile for client. + * \param[in] qos_profile rmw_qos_profile_t Quality of service profile for client. * \param[in] group Callback group to call the service. * \return Shared pointer to the created service. */ @@ -891,7 +891,8 @@ public: /// Return the number of publishers that are advertised on a given topic. /** - * \param[in] topic_name the topic_name on which to count the publishers. + * \param[in] node_name the node_name on which to count the publishers. + * \param[in] namespace_ the namespace of the node associated with the name * \return number of publishers that are advertised on a given topic. * \throws std::runtime_error if publishers could not be counted */ diff --git a/rclcpp/include/rclcpp/parameter_client.hpp b/rclcpp/include/rclcpp/parameter_client.hpp index fa45dd2..0305529 100644 --- a/rclcpp/include/rclcpp/parameter_client.hpp +++ b/rclcpp/include/rclcpp/parameter_client.hpp @@ -48,13 +48,13 @@ public: /// Create an async parameters client. /** - * \param node_base_interface[in] The node base interface of the corresponding node. - * \param node_topics_interface[in] Node topic base interface. - * \param node_graph_interface[in] The node graph interface of the corresponding node. - * \param node_services_interface[in] Node service interface. - * \param remote_node_name[in] (optional) name of the remote node - * \param qos_profile[in] (optional) The rmw qos profile to use to subscribe - * \param group[in] (optional) The async parameter client will be added to this callback group. + * \param[in] node_base_interface The node base interface of the corresponding node. + * \param[in] node_topics_interface Node topic base interface. + * \param[in] node_graph_interface The node graph interface of the corresponding node. + * \param[in] node_services_interface Node service interface. + * \param[in] remote_node_name (optional) name of the remote node + * \param[in] qos_profile (optional) The rmw qos profile to use to subscribe + * \param[in] group (optional) The async parameter client will be added to this callback group. */ RCLCPP_PUBLIC AsyncParametersClient( @@ -68,10 +68,10 @@ public: /// Constructor /** - * \param node[in] The async paramters client will be added to this node. - * \param remote_node_name[in] (optional) name of the remote node - * \param qos_profile[in] (optional) The rmw qos profile to use to subscribe - * \param group[in] (optional) The async parameter client will be added to this callback group. + * \param[in] node The async paramters client will be added to this node. + * \param[in] remote_node_name (optional) name of the remote node + * \param[in] qos_profile (optional) The rmw qos profile to use to subscribe + * \param[in] group (optional) The async parameter client will be added to this callback group. */ RCLCPP_PUBLIC AsyncParametersClient( @@ -82,10 +82,10 @@ public: /// Constructor /** - * \param node[in] The async paramters client will be added to this node. - * \param remote_node_name[in] (optional) name of the remote node - * \param qos_profile[in] (optional) The rmw qos profile to use to subscribe - * \param group[in] (optional) The async parameter client will be added to this callback group. + * \param[in] node The async paramters client will be added to this node. + * \param[in] remote_node_name (optional) name of the remote node + * \param[in] qos_profile (optional) The rmw qos profile to use to subscribe + * \param[in] group (optional) The async parameter client will be added to this callback group. */ RCLCPP_PUBLIC AsyncParametersClient( diff --git a/rclcpp/include/rclcpp/serialization.hpp b/rclcpp/include/rclcpp/serialization.hpp index 97d0449..862c625 100644 --- a/rclcpp/include/rclcpp/serialization.hpp +++ b/rclcpp/include/rclcpp/serialization.hpp @@ -60,7 +60,7 @@ public: /// Serialize a ROS2 message to a serialized stream /** - * \param[in] message The ROS2 message which is read and serialized by rmw. + * \param[in] ros_message The ROS2 message which is read and serialized by rmw. * \param[out] serialized_message The serialized message. */ void serialize_message( @@ -69,7 +69,7 @@ public: /// Deserialize a serialized stream to a ROS message /** * \param[in] serialized_message The serialized message to be converted to ROS2 by rmw. - * \param[out] message The deserialized ROS2 message. + * \param[out] ros_message The deserialized ROS2 message. */ void deserialize_message( const SerializedMessage * serialized_message, void * ros_message) const; diff --git a/rclcpp/include/rclcpp/service.hpp b/rclcpp/include/rclcpp/service.hpp index 2ba6b7f..094b628 100644 --- a/rclcpp/include/rclcpp/service.hpp +++ b/rclcpp/include/rclcpp/service.hpp @@ -237,7 +237,7 @@ public: * rclcpp::create_service(). * * \param[in] node_handle NodeBaseInterface pointer that is used in part of the setup. - * \param[in] service_name Name of the topic to publish to. + * \param[in] service_handle service handle. * \param[in] any_callback User defined callback to call when a client request is received. */ Service( @@ -272,7 +272,7 @@ public: * rclcpp::create_service(). * * \param[in] node_handle NodeBaseInterface pointer that is used in part of the setup. - * \param[in] service_name Name of the topic to publish to. + * \param[in] service_handle service handle. * \param[in] any_callback User defined callback to call when a client request is received. */ Service( diff --git a/rclcpp/include/rclcpp/subscription_factory.hpp b/rclcpp/include/rclcpp/subscription_factory.hpp index fc3933e..694be60 100644 --- a/rclcpp/include/rclcpp/subscription_factory.hpp +++ b/rclcpp/include/rclcpp/subscription_factory.hpp @@ -68,7 +68,7 @@ struct SubscriptionFactory * \param[in] callback The user-defined callback function to receive a message * \param[in] options Additional options for the creation of the Subscription. * \param[in] msg_mem_strat The message memory strategy to use for allocating messages. - * \param[in] subscription_topic_Optinal stats callback for topic_statistics + * \param[in] subscription_topic_stats Optional stats callback for topic_statistics */ template< typename MessageT, diff --git a/rclcpp/include/rclcpp/time.hpp b/rclcpp/include/rclcpp/time.hpp index 64c6126..6782393 100644 --- a/rclcpp/include/rclcpp/time.hpp +++ b/rclcpp/include/rclcpp/time.hpp @@ -48,7 +48,7 @@ public: /// Time constructor /** * \param nanoseconds since time epoch - * \param clock_type clock type + * \param clock clock type */ RCLCPP_PUBLIC explicit Time(int64_t nanoseconds = 0, rcl_clock_type_t clock = RCL_SYSTEM_TIME); @@ -60,7 +60,7 @@ public: /// Time constructor /** * \param time_msg builtin_interfaces time message to copy - * \param clock_type clock type + * \param ros_time clock type * \throws std::runtime_error if seconds are negative */ RCLCPP_PUBLIC @@ -71,7 +71,6 @@ public: /// Time constructor /** * \param time_point rcl_time_point_t structure to copy - * \param clock_type clock type */ RCLCPP_PUBLIC explicit Time(const rcl_time_point_t & time_point); diff --git a/rclcpp/include/rclcpp/timer.hpp b/rclcpp/include/rclcpp/timer.hpp index 66a7529..6f0a0ca 100644 --- a/rclcpp/include/rclcpp/timer.hpp +++ b/rclcpp/include/rclcpp/timer.hpp @@ -166,6 +166,7 @@ public: * \param[in] clock The clock providing the current time. * \param[in] period The interval at which the timer fires. * \param[in] callback User-specified callback function. + * \param[in] context custom context to be used. */ explicit GenericTimer( Clock::SharedPtr clock, std::chrono::nanoseconds period, FunctorT && callback, diff --git a/rclcpp/include/rclcpp/topic_statistics/subscription_topic_statistics.hpp b/rclcpp/include/rclcpp/topic_statistics/subscription_topic_statistics.hpp index e450aa5..46155ca 100644 --- a/rclcpp/include/rclcpp/topic_statistics/subscription_topic_statistics.hpp +++ b/rclcpp/include/rclcpp/topic_statistics/subscription_topic_statistics.hpp @@ -116,7 +116,7 @@ public: /// Set the timer used to publish statistics messages. /** - * \param measurement_timer the timer to fire the publisher, created by the node + * \param publisher_timer the timer to fire the publisher, created by the node */ void set_publisher_timer(rclcpp::TimerBase::SharedPtr publisher_timer) { diff --git a/rclcpp/include/rclcpp/wait_set_template.hpp b/rclcpp/include/rclcpp/wait_set_template.hpp index 2ab6f57..87e3974 100644 --- a/rclcpp/include/rclcpp/wait_set_template.hpp +++ b/rclcpp/include/rclcpp/wait_set_template.hpp @@ -61,6 +61,8 @@ public: * \param[in] subscriptions Vector of subscriptions to be added. * \param[in] guard_conditions Vector of guard conditions to be added. * \param[in] timers Vector of timers to be added. + * \param[in] clients Vector of clients and their associated entity to be added. + * \param[in] services Vector of services and their associated entity to be added. * \param[in] waitables Vector of waitables and their associated entity to be added. * \param[in] context Custom context to be used, defaults to global default. * \throws std::invalid_argument If context is nullptr. diff --git a/rclcpp/include/rclcpp/waitable.hpp b/rclcpp/include/rclcpp/waitable.hpp index 428cc1d..64504f3 100644 --- a/rclcpp/include/rclcpp/waitable.hpp +++ b/rclcpp/include/rclcpp/waitable.hpp @@ -123,7 +123,7 @@ public: RCLCPP_PUBLIC virtual bool - is_ready(rcl_wait_set_t *) = 0; + is_ready(rcl_wait_set_t * wait_set) = 0; /// Execute any entities of the Waitable that are ready. /** diff --git a/rclcpp_action/include/rclcpp_action/create_client.hpp b/rclcpp_action/include/rclcpp_action/create_client.hpp index 2acd4d7..07cf950 100644 --- a/rclcpp_action/include/rclcpp_action/create_client.hpp +++ b/rclcpp_action/include/rclcpp_action/create_client.hpp @@ -30,10 +30,10 @@ namespace rclcpp_action * This function is equivalent to \sa create_client()` however is using the individual * node interfaces to create the client. * - * \param node_base_interface[in] The node base interface of the corresponding node. - * \param node_graph_interface[in] The node graph interface of the corresponding node. - * \param node_logging_interface[in] The node logging interface of the corresponding node. - * \param node_waitables_interface[in] The node waitables interface of the corresponding node. + * \param[in] node_base_interface The node base interface of the corresponding node. + * \param[in] node_graph_interface The node graph interface of the corresponding node. + * \param[in] node_logging_interface The node logging interface of the corresponding node. + * \param[in] node_waitables_interface The node waitables interface of the corresponding node. * \param[in] name The action name. * \param[in] group The action client will be added to this callback group. * If `nullptr`, then the action client is added to the default callback group. diff --git a/rclcpp_action/include/rclcpp_action/create_server.hpp b/rclcpp_action/include/rclcpp_action/create_server.hpp index 2886ee9..9d198c8 100644 --- a/rclcpp_action/include/rclcpp_action/create_server.hpp +++ b/rclcpp_action/include/rclcpp_action/create_server.hpp @@ -39,18 +39,18 @@ namespace rclcpp_action * * \sa Server::Server() for more information. * - * \param node_base_interface[in] The node base interface of the corresponding node. - * \param node_clock_interface[in] The node clock interface of the corresponding node. - * \param node_logging_interface[in] The node logging interface of the corresponding node. - * \param node_waitables_interface[in] The node waitables interface of the corresponding node. - * \param name[in] The action name. + * \param[in] node_base_interface The node base interface of the corresponding node. + * \param[in] node_clock_interface The node clock interface of the corresponding node. + * \param[in] node_logging_interface The node logging interface of the corresponding node. + * \param[in] node_waitables_interface The node waitables interface of the corresponding node. + * \param[in] name The action name. * \param[in] handle_goal A callback that decides if a goal should be accepted or rejected. * \param[in] handle_cancel A callback that decides if a goal should be attempted to be canceled. * The return from this callback only indicates if the server will try to cancel a goal. * It does not indicate if the goal was actually canceled. * \param[in] handle_accepted A callback that is called to give the user a handle to the goal. * \param[in] options options to pass to the underlying `rcl_action_server_t`. - * \param group[in] The action server will be added to this callback group. + * \param[in] group The action server will be added to this callback group. * If `nullptr`, then the action server is added to the default callback group. */ template @@ -117,15 +117,15 @@ create_server( * * \sa Server::Server() for more information. * - * \param node[in] The action server will be added to this node. - * \param name[in] The action name. + * \param[in] node] The action server will be added to this node. + * \param[in] name The action name. * \param[in] handle_goal A callback that decides if a goal should be accepted or rejected. * \param[in] handle_cancel A callback that decides if a goal should be attempted to be canceled. * The return from this callback only indicates if the server will try to cancel a goal. * It does not indicate if the goal was actually canceled. * \param[in] handle_accepted A callback that is called to give the user a handle to the goal. * \param[in] options options to pass to the underlying `rcl_action_server_t`. - * \param group[in] The action server will be added to this callback group. + * \param[in] group The action server will be added to this callback group. * If `nullptr`, then the action server is added to the default callback group. */ template diff --git a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp index 5c234e8..bd2327f 100644 --- a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp +++ b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp @@ -124,7 +124,6 @@ public: /// Create a new lifecycle node with the specified name. /** * \param[in] node_name Name of the node. - * \param[in] namespace_ Namespace of the node. * \param[in] options Additional options to control creation of the node. */ RCLCPP_LIFECYCLE_PUBLIC