From 3c198de5b263e5b681176dac286ba74c4df1d303 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Fri, 10 Jul 2020 22:54:25 +0200 Subject: [PATCH] [Backport Dashing]Fixed doxygen warnings (#1163) (#1208) Signed-off-by: ahcorde --- rclcpp/include/rclcpp/clock.hpp | 6 +++--- .../executors/multi_threaded_executor.hpp | 1 + rclcpp/include/rclcpp/node.hpp | 17 +++++++++++++-- rclcpp/include/rclcpp/parameter_client.hpp | 21 +++++++++++++++++++ rclcpp/include/rclcpp/service.hpp | 20 ++++++++++++++++++ .../include/rclcpp/subscription_factory.hpp | 7 ++++++- rclcpp/include/rclcpp/time.hpp | 15 +++++++++++++ rclcpp/include/rclcpp/timer.hpp | 1 + rclcpp/include/rclcpp/waitable.hpp | 2 +- .../include/rclcpp_action/create_client.hpp | 8 +++---- .../include/rclcpp_action/create_server.hpp | 18 ++++++++-------- .../rclcpp_lifecycle/lifecycle_node.hpp | 1 - 12 files changed, 96 insertions(+), 21 deletions(-) diff --git a/rclcpp/include/rclcpp/clock.hpp b/rclcpp/include/rclcpp/clock.hpp index b9bbe2d41a..0a9b90ed28 100644 --- a/rclcpp/include/rclcpp/clock.hpp +++ b/rclcpp/include/rclcpp/clock.hpp @@ -105,9 +105,9 @@ class Clock * * 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 72df5dd82a..b609561036 100644 --- a/rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp +++ b/rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp @@ -48,6 +48,7 @@ class MultiThreadedExecutor : public executor::Executor * \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 837965c76c..ed6fc3a4ad 100644 --- a/rclcpp/include/rclcpp/node.hpp +++ b/rclcpp/include/rclcpp/node.hpp @@ -337,7 +337,13 @@ class Node : public std::enable_shared_from_this CallbackT callback, rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr); - /* Create and return a Client. */ + /// Create and return a Client. + /** + * \param[in] service_name The topic to service on. + * \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. + */ template typename rclcpp::Client::SharedPtr create_client( @@ -345,7 +351,14 @@ class Node : public std::enable_shared_from_this const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default, rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr); - /* Create and return a Service. */ + /// Create and return a Service. + /** + * \param[in] service_name The topic to service on. + * \param[in] callback User-defined callback function. + * \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. + */ template typename rclcpp::Service::SharedPtr create_service( diff --git a/rclcpp/include/rclcpp/parameter_client.hpp b/rclcpp/include/rclcpp/parameter_client.hpp index 1ef02f87fe..f01ef335c2 100644 --- a/rclcpp/include/rclcpp/parameter_client.hpp +++ b/rclcpp/include/rclcpp/parameter_client.hpp @@ -46,6 +46,15 @@ class AsyncParametersClient public: RCLCPP_SMART_PTR_DEFINITIONS(AsyncParametersClient) + /// Create an async parameters client. + /** + * \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 + */ RCLCPP_PUBLIC AsyncParametersClient( const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface, @@ -55,12 +64,24 @@ class AsyncParametersClient const std::string & remote_node_name = "", const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters); + /// Constructor + /** + * \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 + */ RCLCPP_PUBLIC AsyncParametersClient( const rclcpp::Node::SharedPtr node, const std::string & remote_node_name = "", const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters); + /// Constructor + /** + * \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 + */ RCLCPP_PUBLIC AsyncParametersClient( rclcpp::Node * node, diff --git a/rclcpp/include/rclcpp/service.hpp b/rclcpp/include/rclcpp/service.hpp index 9dc8d027b0..662cbb64e8 100644 --- a/rclcpp/include/rclcpp/service.hpp +++ b/rclcpp/include/rclcpp/service.hpp @@ -156,6 +156,16 @@ class Service : public ServiceBase } } + /// Default constructor. + /** + * The constructor for a Service is almost never called directly. + * Instead, services should be instantiated through the function + * rclcpp::create_service(). + * + * \param[in] node_handle NodeBaseInterface pointer that is used in part of the setup. + * \param[in] service_handle service handle. + * \param[in] any_callback User defined callback to call when a client request is received. + */ Service( std::shared_ptr node_handle, std::shared_ptr service_handle, @@ -174,6 +184,16 @@ class Service : public ServiceBase service_handle_ = service_handle; } + /// Default constructor. + /** + * The constructor for a Service is almost never called directly. + * Instead, services should be instantiated through the function + * rclcpp::create_service(). + * + * \param[in] node_handle NodeBaseInterface pointer that is used in part of the setup. + * \param[in] service_handle service handle. + * \param[in] any_callback User defined callback to call when a client request is received. + */ Service( std::shared_ptr node_handle, rcl_service_t * service_handle, diff --git a/rclcpp/include/rclcpp/subscription_factory.hpp b/rclcpp/include/rclcpp/subscription_factory.hpp index 9b46fe33d2..21dc7805ae 100644 --- a/rclcpp/include/rclcpp/subscription_factory.hpp +++ b/rclcpp/include/rclcpp/subscription_factory.hpp @@ -65,7 +65,12 @@ struct SubscriptionFactory SetupIntraProcessFunction setup_intra_process; }; -/// Return a SubscriptionFactory with functions for creating a SubscriptionT. +/// Return a SubscriptionFactory setup to create a SubscriptionT. +/** + * \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. + */ template< typename MessageT, typename CallbackT, diff --git a/rclcpp/include/rclcpp/time.hpp b/rclcpp/include/rclcpp/time.hpp index c10b6ce23f..fdd61db15a 100644 --- a/rclcpp/include/rclcpp/time.hpp +++ b/rclcpp/include/rclcpp/time.hpp @@ -34,17 +34,32 @@ class Time RCLCPP_PUBLIC Time(int32_t seconds, uint32_t nanoseconds, rcl_clock_type_t clock_type = RCL_SYSTEM_TIME); + /// Time constructor + /** + * \param nanoseconds since time epoch + * \param clock clock type + */ RCLCPP_PUBLIC explicit Time(int64_t nanoseconds = 0, rcl_clock_type_t clock = RCL_SYSTEM_TIME); RCLCPP_PUBLIC Time(const Time & rhs); + /// Time constructor + /** + * \param time_msg builtin_interfaces time message to copy + * \param ros_time clock type + * \throws std::runtime_error if seconds are negative + */ RCLCPP_PUBLIC Time( const builtin_interfaces::msg::Time & time_msg, rcl_clock_type_t ros_time = RCL_ROS_TIME); + /// Time constructor + /** + * \param time_point rcl_time_point_t structure to copy + */ 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 8a6bc2291f..20bdbc1280 100644 --- a/rclcpp/include/rclcpp/timer.hpp +++ b/rclcpp/include/rclcpp/timer.hpp @@ -126,6 +126,7 @@ class GenericTimer : public TimerBase * \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/waitable.hpp b/rclcpp/include/rclcpp/waitable.hpp index 401b88e541..6e15f717d7 100644 --- a/rclcpp/include/rclcpp/waitable.hpp +++ b/rclcpp/include/rclcpp/waitable.hpp @@ -119,7 +119,7 @@ class Waitable 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 762bc5b380..aad9fcb334 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 604011fc6c..39b49ae38d 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 6f7f587488..3d294e2db8 100644 --- a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp +++ b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp @@ -103,7 +103,6 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, /// 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