From 9730ca7cf8295c07be1e048f557da28244a8b32b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Thu, 28 May 2020 08:34:29 +0200 Subject: [PATCH] Improved rclcpp docblock (#1127) * Improved rclcpp docblock Signed-off-by: ahcorde * Improved docblock Signed-off-by: ahcorde * Included feedback Signed-off-by: ahcorde * Added feedback Signed-off-by: ahcorde --- rclcpp/include/rclcpp/client.hpp | 25 +++++++ rclcpp/include/rclcpp/context.hpp | 6 ++ rclcpp/include/rclcpp/event.hpp | 16 +++++ rclcpp/include/rclcpp/executor.hpp | 19 ++++- .../executors/multi_threaded_executor.hpp | 4 ++ .../executors/single_threaded_executor.hpp | 1 + .../static_executor_entities_collector.hpp | 72 ++++++++++++++++++- .../static_single_threaded_executor.hpp | 17 ++++- .../rclcpp/expand_topic_or_service_name.hpp | 2 + rclcpp/include/rclcpp/graph_listener.hpp | 2 + rclcpp/include/rclcpp/init_options.hpp | 16 ++++- rclcpp/include/rclcpp/loaned_message.hpp | 10 +-- rclcpp/include/rclcpp/memory_strategies.hpp | 4 ++ rclcpp/include/rclcpp/message_info.hpp | 3 + rclcpp/include/rclcpp/node.hpp | 42 +++++++++++ rclcpp/include/rclcpp/node_options.hpp | 3 + rclcpp/include/rclcpp/parameter_client.hpp | 40 +++++++++++ rclcpp/include/rclcpp/service.hpp | 31 ++++++++ rclcpp/include/rclcpp/subscription.hpp | 10 ++- rclcpp/include/rclcpp/subscription_base.hpp | 11 ++- .../include/rclcpp/subscription_factory.hpp | 6 ++ rclcpp/include/rclcpp/time.hpp | 39 ++++++++++ rclcpp/include/rclcpp/time_source.hpp | 1 + rclcpp/include/rclcpp/timer.hpp | 10 ++- .../subscription_topic_statistics.hpp | 1 + rclcpp/include/rclcpp/utilities.hpp | 9 +-- rclcpp/include/rclcpp/wait_result.hpp | 9 +++ rclcpp/include/rclcpp/wait_set_template.hpp | 3 +- 28 files changed, 393 insertions(+), 19 deletions(-) diff --git a/rclcpp/include/rclcpp/client.hpp b/rclcpp/include/rclcpp/client.hpp index e6b02f9969..41b49245bb 100644 --- a/rclcpp/include/rclcpp/client.hpp +++ b/rclcpp/include/rclcpp/client.hpp @@ -119,6 +119,7 @@ class ClientBase /// Wait for a service to be ready. /** * \param timeout maximum time to wait + * \return `true` if the service is ready and the timeout is not over, `false` otherwise */ template bool @@ -194,6 +195,17 @@ class Client : public ClientBase RCLCPP_SMART_PTR_DEFINITIONS(Client) + /// Default constructor. + /** + * The constructor for a Client is almost never called directly. + * Instead, clients should be instantiated through the function + * rclcpp::create_client(). + * + * \param[in] node_base NodeBaseInterface pointer that is used in part of the setup. + * \param[in] node_graph The node graph interface of the corresponding node. + * \param[in] service_name Name of the topic to publish to. + * \param[in] client_options options for the subscription. + */ Client( rclcpp::node_interfaces::NodeBaseInterface * node_base, rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph, @@ -248,12 +260,20 @@ class Client : public ClientBase return this->take_type_erased_response(&response_out, request_header_out); } + /// Create a shared pointer with the response type + /** + * \return shared pointer with the response type + */ std::shared_ptr create_response() override { return std::shared_ptr(new typename ServiceT::Response()); } + /// Create a shared pointer with a rmw_request_id_t + /** + * \return shared pointer with a rmw_request_id_t + */ std::shared_ptr create_request_header() override { @@ -262,6 +282,11 @@ class Client : public ClientBase return std::shared_ptr(new rmw_request_id_t); } + /// Handle a server response + /** + * \param[in] request_header used to check if the secuence number is valid + * \param[in] response message with the server response + */ void handle_response( std::shared_ptr request_header, diff --git a/rclcpp/include/rclcpp/context.hpp b/rclcpp/include/rclcpp/context.hpp index 0bfd61955e..57e7375392 100644 --- a/rclcpp/include/rclcpp/context.hpp +++ b/rclcpp/include/rclcpp/context.hpp @@ -103,6 +103,9 @@ class Context : public std::enable_shared_from_this * \param[in] argv argument array which may contain arguments intended for ROS * \param[in] init_options initialization options for rclcpp and underlying layers * \throw ContextAlreadyInitialized if called if init is called more than once + * \throws anything rclcpp::exceptions::throw_from_rcl_error can throw. + * \throws std::runtime_error if the global logging configure mutex is NULL + * \throws exceptions::UnknownROSArgsError if there are unknown ROS arguments */ RCLCPP_PUBLIC virtual @@ -263,6 +266,7 @@ class Context : public std::enable_shared_from_this * \param[in] wait_set Pointer to the rcl_wait_set_t that will be using the * resulting guard condition. * \return Pointer to the guard condition. + * \throws anything rclcpp::exceptions::throw_from_rcl_error can throw. */ RCLCPP_PUBLIC rcl_guard_condition_t * @@ -282,6 +286,8 @@ class Context : public std::enable_shared_from_this * * \param[in] wait_set Pointer to the rcl_wait_set_t that was using the * resulting guard condition. + * \throws anything rclcpp::exceptions::throw_from_rcl_error can throw. + * \throws std::runtime_error if a nonexistent wait set is trying to release sigint guard condition. */ RCLCPP_PUBLIC void diff --git a/rclcpp/include/rclcpp/event.hpp b/rclcpp/include/rclcpp/event.hpp index 988dba29e2..715eb40ad5 100644 --- a/rclcpp/include/rclcpp/event.hpp +++ b/rclcpp/include/rclcpp/event.hpp @@ -29,17 +29,33 @@ class Event public: RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(Event) + /// Default construct + /** + * Set the default value to false + */ RCLCPP_PUBLIC Event(); + /// Set the Event state value to true + /** + * \return The state value before the call. + */ RCLCPP_PUBLIC bool set(); + /// Get the state value of the Event + /** + * \return the Event state value + */ RCLCPP_PUBLIC bool check(); + /// Get the state value of the Event and set to false + /** + * \return the Event state value + */ RCLCPP_PUBLIC bool check_and_clear(); diff --git a/rclcpp/include/rclcpp/executor.hpp b/rclcpp/include/rclcpp/executor.hpp index 4f71ae0052..39acba3ec4 100644 --- a/rclcpp/include/rclcpp/executor.hpp +++ b/rclcpp/include/rclcpp/executor.hpp @@ -88,6 +88,9 @@ class Executor add_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify = true); /// Convenience function which takes Node and forwards NodeBaseInterface. + /** + * \see rclcpp::Executor::add_node + */ RCLCPP_PUBLIC virtual void add_node(std::shared_ptr node_ptr, bool notify = true); @@ -104,6 +107,9 @@ class Executor remove_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify = true); /// Convenience function which takes Node and forwards NodeBaseInterface. + /** + * \see rclcpp::Executor::remove_node + */ RCLCPP_PUBLIC virtual void remove_node(std::shared_ptr node_ptr, bool notify = true); @@ -232,7 +238,10 @@ class Executor } /// Cancel any running spin* function, causing it to return. - /* This function can be called asynchonously from any thread. */ + /** + * This function can be called asynchonously from any thread. + * \throws std::runtime_error if there is an issue triggering the guard condition + */ RCLCPP_PUBLIC void cancel(); @@ -242,6 +251,7 @@ class Executor * Switching the memory strategy while the executor is spinning in another threading could have * unintended consequences. * \param[in] memory_strategy Shared pointer to the memory strategy to set. + * \throws std::runtime_error if memory_strategy is null */ RCLCPP_PUBLIC void @@ -255,8 +265,10 @@ class Executor std::chrono::nanoseconds timeout); /// Find the next available executable and do the work associated with it. - /** \param[in] any_exec Union structure that can hold any executable type (timer, subscription, + /** + * \param[in] any_exec Union structure that can hold any executable type (timer, subscription, * service, client). + * \throws std::runtime_error if there is an issue triggering the guard condition */ RCLCPP_PUBLIC void @@ -279,6 +291,9 @@ class Executor static void execute_client(rclcpp::ClientBase::SharedPtr client); + /** + * \throws std::runtime_error if the wait set can be cleared + */ RCLCPP_PUBLIC void wait_for_work(std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1)); diff --git a/rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp b/rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp index 7cc82c88db..062b6fbbb7 100644 --- a/rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp +++ b/rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp @@ -60,6 +60,10 @@ class MultiThreadedExecutor : public rclcpp::Executor RCLCPP_PUBLIC virtual ~MultiThreadedExecutor(); + /** + * \sa rclcpp::Executor:spin() for more details + * \throws std::runtime_error when spin() called while already spinning + */ RCLCPP_PUBLIC void spin() override; diff --git a/rclcpp/include/rclcpp/executors/single_threaded_executor.hpp b/rclcpp/include/rclcpp/executors/single_threaded_executor.hpp index be1310f8df..9dc6dec57b 100644 --- a/rclcpp/include/rclcpp/executors/single_threaded_executor.hpp +++ b/rclcpp/include/rclcpp/executors/single_threaded_executor.hpp @@ -59,6 +59,7 @@ class SingleThreadedExecutor : public rclcpp::Executor * the process until canceled. * It may be interrupt by a call to rclcpp::Executor::cancel() or by ctrl-c * if the associated context is configured to shutdown on SIGINT. + * \throws std::runtime_error when spin() called while already spinning */ RCLCPP_PUBLIC void diff --git a/rclcpp/include/rclcpp/executors/static_executor_entities_collector.hpp b/rclcpp/include/rclcpp/executors/static_executor_entities_collector.hpp index f9a0525112..f4c8e3544c 100644 --- a/rclcpp/include/rclcpp/executors/static_executor_entities_collector.hpp +++ b/rclcpp/include/rclcpp/executors/static_executor_entities_collector.hpp @@ -47,6 +47,13 @@ class StaticExecutorEntitiesCollector final // Destructor ~StaticExecutorEntitiesCollector(); + /// Initialize StaticExecutorEntitiesCollector + /** + * \param p_wait_set A reference to the wait set to be used in the executor + * \param memory_strategy Shared pointer to the memory strategy to set. + * \param executor_guard_condition executor's guard condition + * \throws std::runtime_error if memory strategy is null + */ RCLCPP_PUBLIC void init( @@ -67,16 +74,26 @@ class StaticExecutorEntitiesCollector final fill_executable_list(); /// Function to reallocate space for entities in the wait set. + /** + * \throws std::runtime_error if wait set couldn't be cleared or resized. + */ RCLCPP_PUBLIC void prepare_wait_set(); /// Function to add_handles_to_wait_set and wait for work and - // block until the wait set is ready or until the timeout has been exceeded. + /** + * block until the wait set is ready or until the timeout has been exceeded. + * \throws std::runtime_error if wait set couldn't be cleared or filled. + * \throws any rcl errors from rcl_wait, \sa rclcpp::exceptions::throw_from_rcl_error() + */ RCLCPP_PUBLIC void refresh_wait_set(std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1)); + /** + * \throws std::runtime_error if it couldn't add guard condition to wait set + */ RCLCPP_PUBLIC bool add_to_wait_set(rcl_wait_set_t * wait_set) override; @@ -85,11 +102,19 @@ class StaticExecutorEntitiesCollector final size_t get_number_of_ready_guard_conditions() override; + /** + * \sa rclcpp::Executor::add_node() + * \throw std::runtime_error if node was already added + */ RCLCPP_PUBLIC void add_node( rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr); + /** + * \sa rclcpp::Executor::remove_node() + * \throw std::runtime_error if no guard condition is associated with node. + */ RCLCPP_PUBLIC bool remove_node( @@ -105,42 +130,87 @@ class StaticExecutorEntitiesCollector final bool is_ready(rcl_wait_set_t * wait_set) override; + /// Return number of timers + /** + * \return number of timers + */ RCLCPP_PUBLIC size_t get_number_of_timers() {return exec_list_.number_of_timers;} + /// Return number of subscriptions + /** + * \return number of subscriptions + */ RCLCPP_PUBLIC size_t get_number_of_subscriptions() {return exec_list_.number_of_subscriptions;} + /// Return number of services + /** + * \return number of services + */ RCLCPP_PUBLIC size_t get_number_of_services() {return exec_list_.number_of_services;} + /// Return number of clients + /** + * \return number of clients + */ RCLCPP_PUBLIC size_t get_number_of_clients() {return exec_list_.number_of_clients;} + /// Return number of waitables + /** + * \return number of waitables + */ RCLCPP_PUBLIC size_t get_number_of_waitables() {return exec_list_.number_of_waitables;} + /** Return a SubscritionBase Sharedptr by index. + * \param[in] i The index of the SubscritionBase + * \return a SubscritionBase shared pointer + * \throws std::out_of_range if the argument is higher than the size of the structrue. + */ RCLCPP_PUBLIC rclcpp::SubscriptionBase::SharedPtr get_subscription(size_t i) {return exec_list_.subscription[i];} + /** Return a TimerBase Sharedptr by index. + * \param[in] i The index of the TimerBase + * \return a TimerBase shared pointer + * \throws std::out_of_range if the argument is higher than the size. + */ RCLCPP_PUBLIC rclcpp::TimerBase::SharedPtr get_timer(size_t i) {return exec_list_.timer[i];} + /** Return a ServiceBase Sharedptr by index. + * \param[in] i The index of the ServiceBase + * \return a ServiceBase shared pointer + * \throws std::out_of_range if the argument is higher than the size. + */ RCLCPP_PUBLIC rclcpp::ServiceBase::SharedPtr get_service(size_t i) {return exec_list_.service[i];} + /** Return a ClientBase Sharedptr by index + * \param[in] i The index of the ClientBase + * \return a ClientBase shared pointer + * \throws std::out_of_range if the argument is higher than the size. + */ RCLCPP_PUBLIC rclcpp::ClientBase::SharedPtr get_client(size_t i) {return exec_list_.client[i];} + /** Return a Waitable Sharedptr by index + * \param[in] i The index of the Waitable + * \return a Waitable shared pointer + * \throws std::out_of_range if the argument is higher than the size. + */ RCLCPP_PUBLIC rclcpp::Waitable::SharedPtr get_waitable(size_t i) {return exec_list_.waitable[i];} diff --git a/rclcpp/include/rclcpp/executors/static_single_threaded_executor.hpp b/rclcpp/include/rclcpp/executors/static_single_threaded_executor.hpp index bf68985812..1e1668bcb3 100644 --- a/rclcpp/include/rclcpp/executors/static_single_threaded_executor.hpp +++ b/rclcpp/include/rclcpp/executors/static_single_threaded_executor.hpp @@ -69,8 +69,11 @@ class StaticSingleThreadedExecutor : public rclcpp::Executor virtual ~StaticSingleThreadedExecutor(); /// Static executor implementation of spin. - // This function will block until work comes in, execute it, and keep blocking. - // It will only be interrupt by a CTRL-C (managed by the global signal handler). + /** + * This function will block until work comes in, execute it, and keep blocking. + * It will only be interrupted by a CTRL-C (managed by the global signal handler). + * \throws std::runtime_error when spin() called while already spinning + */ RCLCPP_PUBLIC void spin() override; @@ -82,6 +85,8 @@ class StaticSingleThreadedExecutor : public rclcpp::Executor * \param[in] notify True to trigger the interrupt guard condition during this function. If * the executor is blocked at the rmw layer while waiting for work and it is notified that a new * node was added, it will wake up. + * \throw std::runtime_error if node was already added or if rcl_trigger_guard_condition + * return an error */ RCLCPP_PUBLIC void @@ -90,6 +95,10 @@ class StaticSingleThreadedExecutor : public rclcpp::Executor bool notify = true) override; /// Convenience function which takes Node and forwards NodeBaseInterface. + /** + * \throw std::runtime_error if node was already added or if rcl_trigger_guard_condition + * returns an error + */ RCLCPP_PUBLIC void add_node(std::shared_ptr node_ptr, bool notify = true) override; @@ -100,6 +109,7 @@ class StaticSingleThreadedExecutor : public rclcpp::Executor * \param[in] notify True to trigger the interrupt guard condition and wake up the executor. * This is useful if the last node was removed from the executor while the executor was blocked * waiting for work in another thread, because otherwise the executor would never be notified. + * \throw std::runtime_error if rcl_trigger_guard_condition returns an error */ RCLCPP_PUBLIC void @@ -108,6 +118,9 @@ class StaticSingleThreadedExecutor : public rclcpp::Executor bool notify = true) override; /// Convenience function which takes Node and forwards NodeBaseInterface. + /** + * \throw std::runtime_error if rcl_trigger_guard_condition returns an error + */ RCLCPP_PUBLIC void remove_node(std::shared_ptr node_ptr, bool notify = true) override; diff --git a/rclcpp/include/rclcpp/expand_topic_or_service_name.hpp b/rclcpp/include/rclcpp/expand_topic_or_service_name.hpp index 5454dfac87..79fbc3e104 100644 --- a/rclcpp/include/rclcpp/expand_topic_or_service_name.hpp +++ b/rclcpp/include/rclcpp/expand_topic_or_service_name.hpp @@ -49,6 +49,8 @@ namespace rclcpp * \throws InvalidServiceNameError if name is invalid and is_service is true * \throws std::bad_alloc if memory cannot be allocated * \throws RCLError if an unexpect error occurs + * \throws std::runtime_error if the topic name is unexpectedly valid or, + * if the rcl name is invalid or if the rcl namespace is invalid */ RCLCPP_PUBLIC std::string diff --git a/rclcpp/include/rclcpp/graph_listener.hpp b/rclcpp/include/rclcpp/graph_listener.hpp index 2adbad4e42..a9871701cb 100644 --- a/rclcpp/include/rclcpp/graph_listener.hpp +++ b/rclcpp/include/rclcpp/graph_listener.hpp @@ -73,6 +73,8 @@ class GraphListener : public std::enable_shared_from_this * This function is thread-safe. * * \throws GraphListenerShutdownError if the GraphListener is shutdown + * \throws std::runtime if the parent context was destroyed + * \throws anything rclcpp::exceptions::throw_from_rcl_error can throw. */ RCLCPP_PUBLIC virtual diff --git a/rclcpp/include/rclcpp/init_options.hpp b/rclcpp/include/rclcpp/init_options.hpp index 7b05ee8d00..447c148e00 100644 --- a/rclcpp/include/rclcpp/init_options.hpp +++ b/rclcpp/include/rclcpp/init_options.hpp @@ -30,11 +30,21 @@ class InitOptions /// If true, the context will be shutdown on SIGINT by the signal handler (if it was installed). bool shutdown_on_sigint = true; - /// Constructor which allows you to specify the allocator used within the init options. + /// Constructor + /** + * It allows you to specify the allocator used within the init options. + * \param[in] allocator used allocate memory within the init options + * \throws anything rclcpp::exceptions::throw_from_rcl_error can throw. + */ RCLCPP_PUBLIC explicit InitOptions(rcl_allocator_t allocator = rcl_get_default_allocator()); /// Constructor which is initialized by an existing init_options. + /** + * Initialized by an existing init_options. + * \param[in] init_options rcl_init_options_t to initialized + * \throws anything rclcpp::exceptions::throw_from_rcl_error can throw. + */ RCLCPP_PUBLIC explicit InitOptions(const rcl_init_options_t & init_options); @@ -62,6 +72,10 @@ class InitOptions ~InitOptions(); /// Return the rcl init options. + /** + * \return the rcl init options. + * \throws anything rclcpp::exceptions::throw_from_rcl_error can throw. + */ RCLCPP_PUBLIC const rcl_init_options_t * get_rcl_init_options() const; diff --git a/rclcpp/include/rclcpp/loaned_message.hpp b/rclcpp/include/rclcpp/loaned_message.hpp index ad086cfd64..50a8766fda 100644 --- a/rclcpp/include/rclcpp/loaned_message.hpp +++ b/rclcpp/include/rclcpp/loaned_message.hpp @@ -52,8 +52,9 @@ class LoanedMessage * However, this user code is ought to be usable even when dynamically linked against * a middleware which doesn't support message loaning in which case the allocator will be used. * - * \param pub rclcpp::Publisher instance to which the memory belongs - * \param allocator Allocator instance in case middleware can not allocate messages + * \param[in] pub rclcpp::Publisher instance to which the memory belongs + * \param[in] allocator Allocator instance in case middleware can not allocate messages + * \throws anything rclcpp::exceptions::throw_from_rcl_error can throw. */ LoanedMessage( const rclcpp::PublisherBase & pub, @@ -98,8 +99,9 @@ class LoanedMessage * However, this user code is ought to be usable even when dynamically linked against * a middleware which doesn't support message loaning in which case the allocator will be used. * - * \param pub rclcpp::Publisher instance to which the memory belongs - * \param allocator Allocator instance in case middleware can not allocate messages + * \param[in] pub rclcpp::Publisher instance to which the memory belongs + * \param[in] allocator Allocator instance in case middleware can not allocate messages + * \throws anything rclcpp::exceptions::throw_from_rcl_error can throw. */ LoanedMessage( const rclcpp::PublisherBase * pub, diff --git a/rclcpp/include/rclcpp/memory_strategies.hpp b/rclcpp/include/rclcpp/memory_strategies.hpp index a3950d9bd0..12730fc6f6 100644 --- a/rclcpp/include/rclcpp/memory_strategies.hpp +++ b/rclcpp/include/rclcpp/memory_strategies.hpp @@ -23,6 +23,10 @@ namespace rclcpp namespace memory_strategies { +/// Create a MemoryStrategy sharedPtr +/** + * \return a MemoryStrategy sharedPtr + */ RCLCPP_PUBLIC memory_strategy::MemoryStrategy::SharedPtr create_default_strategy(); diff --git a/rclcpp/include/rclcpp/message_info.hpp b/rclcpp/include/rclcpp/message_info.hpp index 1653b0a505..452712afdb 100644 --- a/rclcpp/include/rclcpp/message_info.hpp +++ b/rclcpp/include/rclcpp/message_info.hpp @@ -30,6 +30,9 @@ class RCLCPP_PUBLIC MessageInfo MessageInfo() = default; /// Conversion constructor, which is intentionally not marked as explicit. + /** + * \param[in] rmw_message_info message info to initialize the class + */ // cppcheck-suppress noExplicitConstructor MessageInfo(const rmw_message_info_t & rmw_message_info); // NOLINT(runtime/explicit) diff --git a/rclcpp/include/rclcpp/node.hpp b/rclcpp/include/rclcpp/node.hpp index 2f3c00f4f7..f379367d2e 100644 --- a/rclcpp/include/rclcpp/node.hpp +++ b/rclcpp/include/rclcpp/node.hpp @@ -78,6 +78,7 @@ class Node : public std::enable_shared_from_this /** * \param[in] node_name Name of the node. * \param[in] options Additional options to control creation of the node. + * \throws InvalidNamespaceError if the namespace is invalid */ RCLCPP_PUBLIC explicit Node( @@ -89,6 +90,7 @@ class Node : public std::enable_shared_from_this * \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. + * \throws InvalidNamespaceError if the namespace is invalid */ RCLCPP_PUBLIC explicit Node( @@ -122,6 +124,7 @@ class Node : public std::enable_shared_from_this /// Get the fully-qualified name of the node. /** * The fully-qualified name includes the local namespace and name of the node. + * \return fully-qualified name of the node. */ RCLCPP_PUBLIC const char * @@ -685,6 +688,7 @@ class Node : public std::enable_shared_from_this * \throws rclcpp::exceptions::ParameterNotDeclaredException if the * parameter has not been declared and undeclared parameters are not * allowed. + * \throws std::runtime_error if the number of described parameters is more than one */ RCLCPP_PUBLIC rcl_interfaces::msg::ParameterDescriptor @@ -707,6 +711,7 @@ class Node : public std::enable_shared_from_this * \throws rclcpp::exceptions::ParameterNotDeclaredException if any of the * parameters have not been declared and undeclared parameters are not * allowed. + * \throws std::runtime_error if the number of described parameters is more than one */ RCLCPP_PUBLIC std::vector @@ -866,14 +871,30 @@ class Node : public std::enable_shared_from_this std::vector get_node_names() const; + /// Return a map of existing topic names to list of topic types. + /** + * \return a map of existing topic names to list of topic types. + * \throws std::runtime_error anything that rcl_error can throw + */ RCLCPP_PUBLIC std::map> get_topic_names_and_types() const; + /// Return a map of existing service names to list of service types. + /** + * \return a map of existing service names to list of service types. + * \throws std::runtime_error anything that rcl_error can throw + */ RCLCPP_PUBLIC std::map> get_service_names_and_types() const; + /// 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. + * \return number of publishers that are advertised on a given topic. + * \throws std::runtime_error if publishers could not be counted + */ RCLCPP_PUBLIC std::map> get_service_names_and_types_by_node( @@ -884,6 +905,12 @@ class Node : public std::enable_shared_from_this size_t count_publishers(const std::string & topic_name) const; + /// Return the number of subscribers who have created a subscription for a given topic. + /** + * \param[in] topic_name the topic_name on which to count the subscribers. + * \return number of subscribers who have created a subscription for a given topic. + * \throws std::runtime_error if publishers could not be counted + */ RCLCPP_PUBLIC size_t count_subscribers(const std::string & topic_name) const; @@ -953,6 +980,9 @@ class Node : public std::enable_shared_from_this /** * The given Event must be acquire through the get_graph_event() method. * + * \param[in] event pointer to an Event to wait for + * \param[in] timeout nanoseconds to wait for the Event to change the state + * * \throws InvalidEventError if the given event is nullptr * \throws EventNotRegisteredError if the given event was not acquired with * get_graph_event(). @@ -963,14 +993,26 @@ class Node : public std::enable_shared_from_this rclcpp::Event::SharedPtr event, std::chrono::nanoseconds timeout); + /// Get a clock as a non-const shared pointer which is managed by the node. + /** + * \sa rclcpp::node_interfaces::NodeClock::get_clock + */ RCLCPP_PUBLIC rclcpp::Clock::SharedPtr get_clock(); + /// Get a clock as a const shared pointer which is managed by the node. + /** + * \sa rclcpp::node_interfaces::NodeClock::get_clock + */ RCLCPP_PUBLIC rclcpp::Clock::ConstSharedPtr get_clock() const; + /// Returns current time from the time source specified by clock_type. + /** + * \sa rclcpp::Clock::now + */ RCLCPP_PUBLIC Time now() const; diff --git a/rclcpp/include/rclcpp/node_options.hpp b/rclcpp/include/rclcpp/node_options.hpp index 32464c556c..01b0158759 100644 --- a/rclcpp/include/rclcpp/node_options.hpp +++ b/rclcpp/include/rclcpp/node_options.hpp @@ -77,6 +77,9 @@ class NodeOptions * This data structure is created lazily, on the first call to this function. * Repeated calls will not regenerate it unless one of the input settings * changed, like arguments, use_global_arguments, or the rcl allocator. + * + * \return a const rcl_node_options_t structure used by the node + * \throws exceptions::UnknownROSArgsError if there are unknown ROS arguments */ RCLCPP_PUBLIC const rcl_node_options_t * diff --git a/rclcpp/include/rclcpp/parameter_client.hpp b/rclcpp/include/rclcpp/parameter_client.hpp index 021ceb37bd..fa45dd285e 100644 --- a/rclcpp/include/rclcpp/parameter_client.hpp +++ b/rclcpp/include/rclcpp/parameter_client.hpp @@ -46,6 +46,16 @@ class AsyncParametersClient public: RCLCPP_SMART_PTR_DEFINITIONS(AsyncParametersClient) + /// 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. + */ RCLCPP_PUBLIC AsyncParametersClient( const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface, @@ -56,6 +66,13 @@ class AsyncParametersClient const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters, rclcpp::CallbackGroup::SharedPtr group = nullptr); + /// 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. + */ RCLCPP_PUBLIC AsyncParametersClient( const rclcpp::Node::SharedPtr node, @@ -63,6 +80,13 @@ class AsyncParametersClient const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters, rclcpp::CallbackGroup::SharedPtr group = nullptr); + /// 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. + */ RCLCPP_PUBLIC AsyncParametersClient( rclcpp::Node * node, @@ -159,10 +183,26 @@ class AsyncParametersClient options); } + /// Return if the parameter services are ready. + /** + * This method checks the following services: + * - get parameter + * - get parameter + * - set parameters + * - list parameters + * - describe parameters + * + * \return `true` if the service is ready, `false` otherwise + */ RCLCPP_PUBLIC bool service_is_ready() const; + /// Wait for the services to be ready. + /** + * \param timeout maximum time to wait + * \return `true` if the services are ready and the timeout is not over, `false` otherwise + */ template bool wait_for_service( diff --git a/rclcpp/include/rclcpp/service.hpp b/rclcpp/include/rclcpp/service.hpp index abe25867f0..2ba6b7f6a3 100644 --- a/rclcpp/include/rclcpp/service.hpp +++ b/rclcpp/include/rclcpp/service.hpp @@ -156,6 +156,17 @@ class Service : public ServiceBase std::shared_ptr)>; RCLCPP_SMART_PTR_DEFINITIONS(Service) + /// 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_name Name of the topic to publish to. + * \param[in] any_callback User defined callback to call when a client request is received. + * \param[in] service_options options for the subscription. + */ Service( std::shared_ptr node_handle, const std::string & service_name, @@ -219,6 +230,16 @@ class Service : public ServiceBase #endif } + /// 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_name Name of the topic to publish to. + * \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, @@ -244,6 +265,16 @@ class Service : public ServiceBase #endif } + /// 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_name Name of the topic to publish to. + * \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.hpp b/rclcpp/include/rclcpp/subscription.hpp index 97e8714b40..b567d1910e 100644 --- a/rclcpp/include/rclcpp/subscription.hpp +++ b/rclcpp/include/rclcpp/subscription.hpp @@ -94,7 +94,7 @@ class Subscription : public SubscriptionBase * \param[in] callback User defined callback to call when a message is received. * \param[in] options options for the subscription. * \param[in] message_memory_strategy The memory strategy to be used for managing message memory. - * \param[in] subscription_topic_statistics pointer to a topic statistics subcription. + * \param[in] subscription_topic_statistics Optional pointer to a topic statistics subcription. * \throws std::invalid_argument if the QoS is uncompatible with intra-process (if one * of the following conditions are true: qos_profile.history == RMW_QOS_POLICY_HISTORY_KEEP_ALL, * qos_profile.depth == 0 or qos_profile.durability != RMW_QOS_POLICY_DURABILITY_VOLATILE). @@ -295,7 +295,9 @@ class Subscription : public SubscriptionBase } /// Return the borrowed message. - /** \param message message to be returned */ + /** + * \param[inout] message message to be returned + */ void return_message(std::shared_ptr & message) override { @@ -303,6 +305,10 @@ class Subscription : public SubscriptionBase message_memory_strategy_->return_message(typed_message); } + /// Return the borrowed serialized message. + /** + * \param[inout] message serialized message to be returned + */ void return_serialized_message(std::shared_ptr & message) override { diff --git a/rclcpp/include/rclcpp/subscription_base.hpp b/rclcpp/include/rclcpp/subscription_base.hpp index 8156622299..84bb127e60 100644 --- a/rclcpp/include/rclcpp/subscription_base.hpp +++ b/rclcpp/include/rclcpp/subscription_base.hpp @@ -110,6 +110,7 @@ class SubscriptionBase : public std::enable_shared_from_this * May throw runtime_error when an unexpected error occurs. * * \return The actual qos settings. + * \throws std::runtime_error if failed to get qos settings */ RCLCPP_PUBLIC rclcpp::QoS @@ -201,6 +202,10 @@ class SubscriptionBase : public std::enable_shared_from_this const rosidl_message_type_support_t & get_message_type_support_handle() const; + /// Return if the subscription is serialized + /** + * \return `true` if the subscription is serialized, `false` otherwise + */ RCLCPP_PUBLIC bool is_serialized() const; @@ -232,7 +237,11 @@ class SubscriptionBase : public std::enable_shared_from_this uint64_t intra_process_subscription_id, IntraProcessManagerWeakPtr weak_ipm); - /// Return the waitable for intra-process, or nullptr if intra-process is not setup. + /// Return the waitable for intra-process + /** + * \return the waitable sharedpointer for intra-process, or nullptr if intra-process is not setup. + * \throws std::runtime_error if the intra process manager is destroyed + */ RCLCPP_PUBLIC rclcpp::Waitable::SharedPtr get_intra_process_waitable() const; diff --git a/rclcpp/include/rclcpp/subscription_factory.hpp b/rclcpp/include/rclcpp/subscription_factory.hpp index ffab0724c8..fc3933ebcf 100644 --- a/rclcpp/include/rclcpp/subscription_factory.hpp +++ b/rclcpp/include/rclcpp/subscription_factory.hpp @@ -64,6 +64,12 @@ struct SubscriptionFactory }; /// 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. + * \param[in] subscription_topic_Optinal stats callback for topic_statistics + */ template< typename MessageT, typename CallbackT, diff --git a/rclcpp/include/rclcpp/time.hpp b/rclcpp/include/rclcpp/time.hpp index a80201a356..64c6126316 100644 --- a/rclcpp/include/rclcpp/time.hpp +++ b/rclcpp/include/rclcpp/time.hpp @@ -40,6 +40,7 @@ class Time * \param seconds part of the time in seconds since time epoch * \param nanoseconds part of the time in nanoseconds since time epoch * \param clock_type clock type + * \throws std::runtime_error if seconds are negative */ RCLCPP_PUBLIC Time(int32_t seconds, uint32_t nanoseconds, rcl_clock_type_t clock_type = RCL_SYSTEM_TIME); @@ -60,6 +61,7 @@ class Time /** * \param time_msg builtin_interfaces time message to copy * \param clock_type clock type + * \throws std::runtime_error if seconds are negative */ RCLCPP_PUBLIC Time( @@ -82,6 +84,9 @@ class Time RCLCPP_PUBLIC operator builtin_interfaces::msg::Time() const; + /** + * \throws std::runtime_error if seconds are negative + */ RCLCPP_PUBLIC Time & operator=(const Time & rhs); @@ -90,6 +95,9 @@ class Time Time & operator=(const builtin_interfaces::msg::Time & time_msg); + /** + * \throws std::runtime_error if the time sources are different + */ RCLCPP_PUBLIC bool operator==(const rclcpp::Time & rhs) const; @@ -98,38 +106,66 @@ class Time bool operator!=(const rclcpp::Time & rhs) const; + /** + * \throws std::runtime_error if the time sources are different + */ RCLCPP_PUBLIC bool operator<(const rclcpp::Time & rhs) const; + /** + * \throws std::runtime_error if the time sources are different + */ RCLCPP_PUBLIC bool operator<=(const rclcpp::Time & rhs) const; + /** + * \throws std::runtime_error if the time sources are different + */ RCLCPP_PUBLIC bool operator>=(const rclcpp::Time & rhs) const; + /** + * \throws std::runtime_error if the time sources are different + */ RCLCPP_PUBLIC bool operator>(const rclcpp::Time & rhs) const; + /** + * \throws std::overflow_error if addition leads to overflow + */ RCLCPP_PUBLIC Time operator+(const rclcpp::Duration & rhs) const; + /** + * \throws std::runtime_error if the time sources are different + * \throws std::overflow_error if addition leads to overflow + */ RCLCPP_PUBLIC Duration operator-(const rclcpp::Time & rhs) const; + /** + * \throws std::overflow_error if addition leads to overflow + */ RCLCPP_PUBLIC Time operator-(const rclcpp::Duration & rhs) const; + /** + * \throws std::overflow_error if addition leads to overflow + */ RCLCPP_PUBLIC Time & operator+=(const rclcpp::Duration & rhs); + /** + * \throws std::overflow_error if addition leads to overflow + */ RCLCPP_PUBLIC Time & operator-=(const rclcpp::Duration & rhs); @@ -174,6 +210,9 @@ class Time friend Clock; // Allow clock to manipulate internal data }; +/** + * \throws std::overflow_error if addition leads to overflow + */ Time operator+(const rclcpp::Duration & lhs, const rclcpp::Time & rhs); diff --git a/rclcpp/include/rclcpp/time_source.hpp b/rclcpp/include/rclcpp/time_source.hpp index 86f62a6cab..74bf38e894 100644 --- a/rclcpp/include/rclcpp/time_source.hpp +++ b/rclcpp/include/rclcpp/time_source.hpp @@ -87,6 +87,7 @@ class TimeSource /// Attach a clock to the time source to be updated /** + * \param[in] clock to attach to the time source * \throws std::invalid_argument the time source must be a RCL_ROS_TIME otherwise throws an exception */ RCLCPP_PUBLIC diff --git a/rclcpp/include/rclcpp/timer.hpp b/rclcpp/include/rclcpp/timer.hpp index 3f3b4d80b7..7fc375dace 100644 --- a/rclcpp/include/rclcpp/timer.hpp +++ b/rclcpp/include/rclcpp/timer.hpp @@ -100,7 +100,10 @@ class TimerBase get_timer_handle(); /// Check how long the timer has until its next scheduled callback. - /** \return A std::chrono::duration representing the relative time until the next callback. */ + /** + * \return A std::chrono::duration representing the relative time until the next callback. + * \throws std::runtime_error if the rcl_timer_get_time_until_next_call returns a failure + */ RCLCPP_PUBLIC std::chrono::nanoseconds time_until_trigger(); @@ -114,6 +117,7 @@ class TimerBase * This function expects its caller to immediately trigger the callback after this function, * since it maintains the last time the callback was triggered. * \return True if the timer needs to trigger. + * \throws std::runtime_error if it failed to check timer */ RCLCPP_PUBLIC bool is_ready(); @@ -185,6 +189,10 @@ class GenericTimer : public TimerBase cancel(); } + /** + * \sa rclcpp::TimerBase::execute_callback + * \throws std::runtime_error if it failed to notify timer that callback occurred + */ void execute_callback() override { diff --git a/rclcpp/include/rclcpp/topic_statistics/subscription_topic_statistics.hpp b/rclcpp/include/rclcpp/topic_statistics/subscription_topic_statistics.hpp index 37a2804cbb..e450aa5d65 100644 --- a/rclcpp/include/rclcpp/topic_statistics/subscription_topic_statistics.hpp +++ b/rclcpp/include/rclcpp/topic_statistics/subscription_topic_statistics.hpp @@ -75,6 +75,7 @@ class SubscriptionTopicStatistics * topic source * \param publisher instance constructed by the node in order to publish statistics data. * This class owns the publisher. + * \throws std::invalid_argument if publisher pointer is nullptr */ SubscriptionTopicStatistics( const std::string & node_name, diff --git a/rclcpp/include/rclcpp/utilities.hpp b/rclcpp/include/rclcpp/utilities.hpp index d876b2d1d9..2b6a3db37f 100644 --- a/rclcpp/include/rclcpp/utilities.hpp +++ b/rclcpp/include/rclcpp/utilities.hpp @@ -136,7 +136,7 @@ remove_ros_arguments(int argc, char const * const argv[]); * If nullptr is given for the context, then the global context is used, i.e. * the context initialized by rclcpp::init(). * - * \param[in] context Check for shutdown of this Context. + * \param[in] context Optional check for shutdown of this Context. * \return true if shutdown has been called, false otherwise */ RCLCPP_PUBLIC @@ -150,7 +150,7 @@ ok(rclcpp::Context::SharedPtr context = nullptr); * * Deprecated, as it is no longer different from rcl_ok(). * - * \param[in] context Check for initialization of this Context. + * \param[in] context Optional check for initialization of this Context. * \return true if the context is initialized, and false otherwise */ [[deprecated("use the function ok() instead, which has the same usage.")]] @@ -168,7 +168,8 @@ is_initialized(rclcpp::Context::SharedPtr context = nullptr); * This will also cause the "on_shutdown" callbacks to be called. * * \sa rclcpp::Context::shutdown() - * \param[in] context to be shutdown + * \param[in] context Optional to be shutdown + * \param[in] reason Optional string passed to the context shutdown method * \return true if shutdown was successful, false if context was already shutdown */ RCLCPP_PUBLIC @@ -206,7 +207,7 @@ on_shutdown(std::function callback, rclcpp::Context::SharedPtr context = * the context initialized by rclcpp::init(). * * \param[in] nanoseconds A std::chrono::duration representing how long to sleep for. - * \param[in] context which may interrupt this sleep + * \param[in] context Optional which may interrupt this sleep * \return true if the condition variable did not timeout. */ RCLCPP_PUBLIC diff --git a/rclcpp/include/rclcpp/wait_result.hpp b/rclcpp/include/rclcpp/wait_result.hpp index 0dfa6974ea..e879043d04 100644 --- a/rclcpp/include/rclcpp/wait_result.hpp +++ b/rclcpp/include/rclcpp/wait_result.hpp @@ -58,6 +58,7 @@ class WaitResult final /** * \param[in] wait_set A reference to the wait set, which this class * will keep for the duration of its lifetime. + * \return a WaitResult from a "ready" result. */ static WaitResult @@ -90,6 +91,10 @@ class WaitResult final } /// Return the rcl wait set. + /** + * \return const rcl wait set. + * \throws std::runtime_error if the class cannot access wait set when the result was not ready + */ const WaitSetT & get_wait_set() const { @@ -102,6 +107,10 @@ class WaitResult final } /// Return the rcl wait set. + /** + * \return rcl wait set. + * \throws std::runtime_error if the class cannot access wait set when the result was not ready + */ WaitSetT & get_wait_set() { diff --git a/rclcpp/include/rclcpp/wait_set_template.hpp b/rclcpp/include/rclcpp/wait_set_template.hpp index 1c9b072275..2ab6f57ba1 100644 --- a/rclcpp/include/rclcpp/wait_set_template.hpp +++ b/rclcpp/include/rclcpp/wait_set_template.hpp @@ -643,7 +643,8 @@ class WaitSetTemplate final : private SynchronizationPolicy, private StoragePoli * when time_to_wait is < 0, or * \returns Empty if the wait set is empty, avoiding the possibility of * waiting indefinitely on an empty wait set. - * \throws rclcpp::exceptions::RCLError on unhandled rcl errors + * \throws rclcpp::exceptions::RCLError on unhandled rcl errors or, + * \throws std::runtime_error if unknown WaitResultKind */ template RCUTILS_WARN_UNUSED