From 061fea87919fb47e87b5b45a4ef8438942d3c801 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Mon, 4 May 2020 16:37:54 +0200 Subject: [PATCH 1/3] Added docblock in rclcpp Signed-off-by: ahcorde --- rclcpp/include/rclcpp/client.hpp | 20 +++++++ rclcpp/include/rclcpp/clock.hpp | 2 + rclcpp/include/rclcpp/duration.hpp | 50 ++++++++++++++-- rclcpp/include/rclcpp/node.hpp | 19 +++++- rclcpp/include/rclcpp/parameter.hpp | 16 +++++ rclcpp/include/rclcpp/publisher.hpp | 11 ++++ rclcpp/include/rclcpp/qos.hpp | 60 +++++++++++++++++++ rclcpp/include/rclcpp/rclcpp.hpp | 1 + rclcpp/include/rclcpp/service.hpp | 12 ++++ rclcpp/include/rclcpp/subscription.hpp | 5 ++ .../include/rclcpp/subscription_options.hpp | 4 ++ rclcpp/include/rclcpp/time.hpp | 59 +++++++++++++++++- rclcpp/include/rclcpp/time_source.hpp | 32 ++++++++++ rclcpp/include/rclcpp/timer.hpp | 28 +++++++++ 14 files changed, 308 insertions(+), 11 deletions(-) diff --git a/rclcpp/include/rclcpp/client.hpp b/rclcpp/include/rclcpp/client.hpp index f7f1d5cb8c..20b5d91b82 100644 --- a/rclcpp/include/rclcpp/client.hpp +++ b/rclcpp/include/rclcpp/client.hpp @@ -84,22 +84,42 @@ class ClientBase bool take_type_erased_response(void * response_out, rmw_request_id_t & request_header_out); + /// Return the name of the node. + /** \return The name of the node. */ RCLCPP_PUBLIC const char * get_service_name() const; + /// Return the rcl_client_t client handle in a std::shared_ptr. + /** + * This handle remains valid after the Client is destroyed. + * The actual rcl client is not finalized until it is out of scope everywhere. + */ RCLCPP_PUBLIC std::shared_ptr get_client_handle(); + /// Return the rcl_client_t client handle in a std::shared_ptr. + /** + * This handle remains valid after the Client is destroyed. + * The actual rcl client is not finalized until it is out of scope everywhere. + */ RCLCPP_PUBLIC std::shared_ptr get_client_handle() const; + /// Return if the service is ready. + /** + * \return `true` if the service is ready, `false` otherwise + */ RCLCPP_PUBLIC bool service_is_ready() const; + /// Wait for a service to be ready. + /** + * \param timeout maximum time to wait + */ template bool wait_for_service( diff --git a/rclcpp/include/rclcpp/clock.hpp b/rclcpp/include/rclcpp/clock.hpp index 3b5b22515a..211966ee41 100644 --- a/rclcpp/include/rclcpp/clock.hpp +++ b/rclcpp/include/rclcpp/clock.hpp @@ -89,6 +89,7 @@ class Clock bool ros_time_is_active(); + /// Return the rcl_clock_t clock handle RCLCPP_PUBLIC rcl_clock_t * get_clock_handle() noexcept; @@ -97,6 +98,7 @@ class Clock rcl_clock_type_t get_clock_type() const noexcept; + /// Get the clock's mutex RCLCPP_PUBLIC std::mutex & get_clock_mutex() noexcept; diff --git a/rclcpp/include/rclcpp/duration.hpp b/rclcpp/include/rclcpp/duration.hpp index 5e09cc5cb1..115b7040ab 100644 --- a/rclcpp/include/rclcpp/duration.hpp +++ b/rclcpp/include/rclcpp/duration.hpp @@ -26,11 +26,22 @@ namespace rclcpp class RCLCPP_PUBLIC Duration { public: + /// Duration constructor. + /** + * Initializes the time values for seconds and nanoseconds individually. + * Large values for nsecs are wrapped automatically with the remainder added to secs. + * Both inputs must be integers. + * Durations can be negative. + * + * \param seconds time in seconds + * \param nanoseconds time in seconds + */ Duration(int32_t seconds, uint32_t nanoseconds); - // This constructor matches any numeric value - ints or floats + // This constructor matches any numeric value - ints or floats. explicit Duration(rcl_duration_value_t nanoseconds); + // This constructor matches std::chrono::nanoseconds. explicit Duration(std::chrono::nanoseconds nanoseconds); // This constructor matches any std::chrono value other than nanoseconds @@ -44,62 +55,90 @@ class RCLCPP_PUBLIC Duration // cppcheck-suppress noExplicitConstructor Duration(const builtin_interfaces::msg::Duration & duration_msg); // NOLINT(runtime/explicit) + /// Time constructor + /** + * \param duration rcl_duration_t structure to copy. + */ explicit Duration(const rcl_duration_t & duration); + /// Copy constructor. Duration(const Duration & rhs); + /// Duration destructor. virtual ~Duration() = default; + /// Return a builtin_interfaces::msg::Duration object based operator builtin_interfaces::msg::Duration() const; // cppcheck-suppress operatorEq // this is a false positive from cppcheck Duration & operator=(const Duration & rhs); + /// Copy assign operator from a builtin_interfaces::msg::Duration. Duration & operator=(const builtin_interfaces::msg::Duration & Duration_msg); + /// Equal operator. bool operator==(const rclcpp::Duration & rhs) const; + /// Less than operator. bool operator<(const rclcpp::Duration & rhs) const; + /// Less or equal than operator. bool operator<=(const rclcpp::Duration & rhs) const; + /// Greater or equal than operator. bool operator>=(const rclcpp::Duration & rhs) const; + /// Greater than operator. bool operator>(const rclcpp::Duration & rhs) const; + /// Addition operator. Duration operator+(const rclcpp::Duration & rhs) const; + /// Subtraction operator. Duration operator-(const rclcpp::Duration & rhs) const; + /// Get the maximum duration value. + /** + * \return the maximum duration value + */ static Duration max(); + /// Multiplication operator. Duration operator*(double scale) const; + /// Get duration in nanosecods + /** + * \return the duration in nanoseconds as a rcl_duration_value_t. + */ rcl_duration_value_t nanoseconds() const; - /// \return the duration in seconds as a floating point number. - /// \warning Depending on sizeof(double) there could be significant precision loss. - /// When an exact time is required use nanoseconds() instead. + /// Get duration in seconds + /** + * \warning Depending on sizeof(double) there could be significant precision loss. + * When an exact time is required use nanoseconds() instead. + * \return the duration in seconds as a floating point number. + */ double seconds() const; - // Create a duration object from a floating point number representing seconds + /// Create a duration object from a floating point number representing seconds static Duration from_seconds(double seconds); + /// Convert Duration in to std::chrono. template DurationT to_chrono() const @@ -107,6 +146,7 @@ class RCLCPP_PUBLIC Duration return std::chrono::duration_cast(std::chrono::nanoseconds(this->nanoseconds())); } + /// Convert Duration into rmw_time_t. rmw_time_t to_rmw_time() const; diff --git a/rclcpp/include/rclcpp/node.hpp b/rclcpp/include/rclcpp/node.hpp index 6131fef95a..2b0faf97e9 100644 --- a/rclcpp/include/rclcpp/node.hpp +++ b/rclcpp/include/rclcpp/node.hpp @@ -186,8 +186,8 @@ class Node : public std::enable_shared_from_this /// Create and return a Subscription. /** * \param[in] topic_name The topic to subscribe on. + * \param[in] qos QoS profile for Subcription. * \param[in] callback The user-defined callback function to receive a message - * \param[in] qos_history_depth The depth of the subscription's incoming message queue. * \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. * \return Shared pointer to the created subscription. @@ -229,7 +229,13 @@ class Node : public std::enable_shared_from_this CallbackT callback, rclcpp::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] 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( @@ -237,7 +243,14 @@ class Node : public std::enable_shared_from_this const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default, rclcpp::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] 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.hpp b/rclcpp/include/rclcpp/parameter.hpp index e01d5aa772..9e56c4f8ef 100644 --- a/rclcpp/include/rclcpp/parameter.hpp +++ b/rclcpp/include/rclcpp/parameter.hpp @@ -83,18 +83,22 @@ class Parameter bool operator!=(const Parameter & rhs) const; + /// Get the type of the parameter RCLCPP_PUBLIC ParameterType get_type() const; + /// Get the type name of the parameter RCLCPP_PUBLIC std::string get_type_name() const; + /// Get the name of the parameter RCLCPP_PUBLIC const std::string & get_name() const; + /// Get value of parameter as a parameter message. RCLCPP_PUBLIC rcl_interfaces::msg::ParameterValue get_value_message() const; @@ -117,50 +121,62 @@ class Parameter decltype(auto) get_value() const; + /// Get value of parameter as boolean. RCLCPP_PUBLIC bool as_bool() const; + /// Get value of parameter as integer. RCLCPP_PUBLIC int64_t as_int() const; + /// Get value of parameter as double. RCLCPP_PUBLIC double as_double() const; + /// Get value of parameter as string. RCLCPP_PUBLIC const std::string & as_string() const; + /// Get value of parameter as byte array (vector). RCLCPP_PUBLIC const std::vector & as_byte_array() const; + /// Get value of parameter as bool array (vector). RCLCPP_PUBLIC const std::vector & as_bool_array() const; + /// Get value of parameter as integer array (vector). RCLCPP_PUBLIC const std::vector & as_integer_array() const; + /// Get value of parameter as double array (vector). RCLCPP_PUBLIC const std::vector & as_double_array() const; + /// Get value of parameter as string array (vector). RCLCPP_PUBLIC const std::vector & as_string_array() const; + /// Convert a parameter message in a Parameter class object. RCLCPP_PUBLIC static Parameter from_parameter_msg(const rcl_interfaces::msg::Parameter & parameter); + /// Convert the class in a parameter message. RCLCPP_PUBLIC rcl_interfaces::msg::Parameter to_parameter_msg() const; + /// Get value of parameter as a string. RCLCPP_PUBLIC std::string value_to_string() const; diff --git a/rclcpp/include/rclcpp/publisher.hpp b/rclcpp/include/rclcpp/publisher.hpp index abe259b31d..ebe349cd99 100644 --- a/rclcpp/include/rclcpp/publisher.hpp +++ b/rclcpp/include/rclcpp/publisher.hpp @@ -59,6 +59,17 @@ class Publisher : public PublisherBase RCLCPP_SMART_PTR_DEFINITIONS(Publisher) + /// Default constructor. + /** + * The constructor for a Publisher is almost never called directly. + * Instead, subscriptions should be instantiated through the function + * rclcpp::create_publisher(). + * + * \param[in] node_base NodeBaseInterface pointer that is used in part of the setup. + * \param[in] topic Name of the topic to publish to. + * \param[in] qos QoS profile for Subcription. + * \param[in] options options for the subscription. + */ Publisher( rclcpp::node_interfaces::NodeBaseInterface * node_base, const std::string & topic, diff --git a/rclcpp/include/rclcpp/qos.hpp b/rclcpp/include/rclcpp/qos.hpp index 244ac699dc..ac016efec5 100644 --- a/rclcpp/include/rclcpp/qos.hpp +++ b/rclcpp/include/rclcpp/qos.hpp @@ -161,6 +161,18 @@ bool operator==(const QoS & left, const QoS & right); RCLCPP_PUBLIC bool operator!=(const QoS & left, const QoS & right); +/** + * Sensor Data QoS class + * - History: Keep last, + * - Depth: 5, + * - Reliability: Best effort, + * - Durability: Volatile, + * - Deadline: Default, + * - Lifespan: Default, + * - Liveliness: System default, + * - Liveliness lease duration: default, + * - avoid ros namespace conventions: false + */ class RCLCPP_PUBLIC SensorDataQoS : public QoS { public: @@ -171,6 +183,18 @@ class RCLCPP_PUBLIC SensorDataQoS : public QoS )); }; +/** + * Parameters QoS class + * - History: Keep last, + * - Depth: 1000, + * - Reliability: Reliable, + * - Durability: Volatile, + * - Deadline: Default, + * - Lifespan: Default, + * - Liveliness: System default, + * - Liveliness lease duration: default, + * - Avoid ros namespace conventions: false + */ class RCLCPP_PUBLIC ParametersQoS : public QoS { public: @@ -181,6 +205,18 @@ class RCLCPP_PUBLIC ParametersQoS : public QoS )); }; +/** + * Services QoS class + * - History: Keep last, + * - Depth: 10, + * - Reliability: Reliable, + * - Durability: Volatile, + * - Deadline: Default, + * - Lifespan: Default, + * - Liveliness: System default, + * - Liveliness lease duration: default, + * - Avoid ros namespace conventions: false + */ class RCLCPP_PUBLIC ServicesQoS : public QoS { public: @@ -191,6 +227,18 @@ class RCLCPP_PUBLIC ServicesQoS : public QoS )); }; +/** + * Parameter events QoS class + * - History: Keep last, + * - Depth: 1000, + * - Reliability: Reliable, + * - Durability: Volatile, + * - Deadline: Default, + * - Lifespan: Default, + * - Liveliness: System default, + * - Liveliness lease duration: default, + * - Avoid ros namespace conventions: false + */ class RCLCPP_PUBLIC ParameterEventsQoS : public QoS { public: @@ -201,6 +249,18 @@ class RCLCPP_PUBLIC ParameterEventsQoS : public QoS )); }; +/** + * System defaults QoS class + * - History: System default, + * - Depth: System default, + * - Reliability: System default, + * - Durability: System default, + * - Deadline: Default, + * - Lifespan: Default, + * - Liveliness: System default, + * - Liveliness lease duration: System default, + * - Avoid ros namespace conventions: false + */ class RCLCPP_PUBLIC SystemDefaultsQoS : public QoS { public: diff --git a/rclcpp/include/rclcpp/rclcpp.hpp b/rclcpp/include/rclcpp/rclcpp.hpp index 556085ee07..dc22c7e649 100644 --- a/rclcpp/include/rclcpp/rclcpp.hpp +++ b/rclcpp/include/rclcpp/rclcpp.hpp @@ -128,6 +128,7 @@ * - rclcpp/context.hpp * - rclcpp/contexts/default_context.hpp * - Various utilities: + * - rclcpp/duration.hpp * - rclcpp/function_traits.hpp * - rclcpp/macros.hpp * - rclcpp/scope_exit.hpp diff --git a/rclcpp/include/rclcpp/service.hpp b/rclcpp/include/rclcpp/service.hpp index de720109a6..6111efa09e 100644 --- a/rclcpp/include/rclcpp/service.hpp +++ b/rclcpp/include/rclcpp/service.hpp @@ -50,14 +50,26 @@ class ServiceBase RCLCPP_PUBLIC virtual ~ServiceBase(); + /// Return the name of the node. + /** \return The name of the node. */ RCLCPP_PUBLIC const char * get_service_name(); + /// Return the rcl_client_t client handle in a std::shared_ptr. + /** + * This handle remains valid after the Client is destroyed. + * The actual rcl client is not finalized until it is out of scope everywhere. + */ RCLCPP_PUBLIC std::shared_ptr get_service_handle(); + /// Return the rcl_client_t client handle in a std::shared_ptr. + /** + * This handle remains valid after the Client is destroyed. + * The actual rcl client is not finalized until it is out of scope everywhere. + */ RCLCPP_PUBLIC std::shared_ptr get_service_handle() const; diff --git a/rclcpp/include/rclcpp/subscription.hpp b/rclcpp/include/rclcpp/subscription.hpp index 2b8108fc94..97e8714b40 100644 --- a/rclcpp/include/rclcpp/subscription.hpp +++ b/rclcpp/include/rclcpp/subscription.hpp @@ -90,9 +90,14 @@ class Subscription : public SubscriptionBase * \param[in] node_base NodeBaseInterface pointer that is used in part of the setup. * \param[in] type_support_handle rosidl type support struct, for the Message type of the topic. * \param[in] topic_name Name of the topic to subscribe to. + * \param[in] qos QoS profile for Subcription. * \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. + * \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). */ Subscription( rclcpp::node_interfaces::NodeBaseInterface * node_base, diff --git a/rclcpp/include/rclcpp/subscription_options.hpp b/rclcpp/include/rclcpp/subscription_options.hpp index 12275d74fe..58a6b970f6 100644 --- a/rclcpp/include/rclcpp/subscription_options.hpp +++ b/rclcpp/include/rclcpp/subscription_options.hpp @@ -89,6 +89,10 @@ struct SubscriptionOptionsWithAllocator : public SubscriptionOptionsBase {} /// Convert this class, with a rclcpp::QoS, into an rcl_subscription_options_t. + /** + * \param qos QoS profile. + * \return rcl_subscription_options_t structure based on the rclcpp::QoS + */ template rcl_subscription_options_t to_rcl_subscription_options(const rclcpp::QoS & qos) const diff --git a/rclcpp/include/rclcpp/time.hpp b/rclcpp/include/rclcpp/time.hpp index d8f65c8672..eb247bd1b3 100644 --- a/rclcpp/include/rclcpp/time.hpp +++ b/rclcpp/include/rclcpp/time.hpp @@ -31,96 +31,149 @@ class Clock; class Time { public: + /// Time constructor + /** + * \param seconds since time epoch + * \param nanoseconds since time epoch + * \param clock_type clock type + */ 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_type clock type + */ RCLCPP_PUBLIC explicit Time(int64_t nanoseconds = 0, rcl_clock_type_t clock = RCL_SYSTEM_TIME); + /// Copy constructor RCLCPP_PUBLIC Time(const Time & rhs); + /// Time constructor + /** + * \param time_msg builtin_interfaces time message to copy + * \param clock_type clock type + */ 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 + * \param clock_type clock type + */ RCLCPP_PUBLIC explicit Time(const rcl_time_point_t & time_point); + /// Time destructor RCLCPP_PUBLIC virtual ~Time(); + /// Return a builtin_interfaces::msg::Time object based RCLCPP_PUBLIC operator builtin_interfaces::msg::Time() const; + /// Copy assign operator RCLCPP_PUBLIC Time & operator=(const Time & rhs); + /// Copy assign operator from a builtin_interfaces::msg::Time RCLCPP_PUBLIC Time & operator=(const builtin_interfaces::msg::Time & time_msg); + /// Equal operator. RCLCPP_PUBLIC bool operator==(const rclcpp::Time & rhs) const; + /// Not equal operator. RCLCPP_PUBLIC bool operator!=(const rclcpp::Time & rhs) const; + /// Less than operator. RCLCPP_PUBLIC bool operator<(const rclcpp::Time & rhs) const; + /// Less or equal than operator. RCLCPP_PUBLIC bool operator<=(const rclcpp::Time & rhs) const; + /// Greater or equal than operator. RCLCPP_PUBLIC bool operator>=(const rclcpp::Time & rhs) const; + /// Greater than operator. RCLCPP_PUBLIC bool operator>(const rclcpp::Time & rhs) const; + /// Addition operator with a rclcpp::Duration. RCLCPP_PUBLIC Time operator+(const rclcpp::Duration & rhs) const; + /// Subtraction operator. RCLCPP_PUBLIC Duration operator-(const rclcpp::Time & rhs) const; + /// Subtraction operator with a rclcpp::Duration. RCLCPP_PUBLIC Time operator-(const rclcpp::Duration & rhs) const; + /// Addition assigment operator with a rclcpp::Duration. RCLCPP_PUBLIC Time & operator+=(const rclcpp::Duration & rhs); + /// Subtraction assigment operator with a rclcpp::Duration. RCLCPP_PUBLIC Time & operator-=(const rclcpp::Duration & rhs); + /// Get the nanoseconds since epoch + /** + * \return the nanoseconds since epoch as a floating point number. + */ RCLCPP_PUBLIC rcl_time_point_value_t nanoseconds() const; + /// Get the maximum time value + /** + * \return the maximum time value + */ RCLCPP_PUBLIC static Time max(); - /// \return the seconds since epoch as a floating point number. - /// \warning Depending on sizeof(double) there could be significant precision loss. - /// When an exact time is required use nanoseconds() instead. + /// Get the seconds since epoch + /** + * \warning Depending on sizeof(double) there could be significant precision loss. + * When an exact time is required use nanoseconds() instead. + * + * \return the seconds since epoch as a floating point number. + */ RCLCPP_PUBLIC double seconds() const; + /// Get the clock type + /** + * \return the clock type + */ RCLCPP_PUBLIC rcl_clock_type_t get_clock_type() const; diff --git a/rclcpp/include/rclcpp/time_source.hpp b/rclcpp/include/rclcpp/time_source.hpp index 9dd4023d42..546ff184e4 100644 --- a/rclcpp/include/rclcpp/time_source.hpp +++ b/rclcpp/include/rclcpp/time_source.hpp @@ -35,15 +35,42 @@ class Clock; class TimeSource { public: + /// Constructor + /** + * The node will be attached to the time source. + * + * \param node std::shared pointer to a initialized node + */ RCLCPP_PUBLIC explicit TimeSource(rclcpp::Node::SharedPtr node); + /// Empty constructor + /** + * An Empty TimeSource class + */ RCLCPP_PUBLIC TimeSource(); + /// Attack node to the time source. + /** + * \param node std::shared pointer to a initialized node + */ RCLCPP_PUBLIC void attachNode(rclcpp::Node::SharedPtr node); + /// Attack node to the time source. + /** + * If the parameter `use_sim_time` is `true` then the source time is the simulation time, + * otherwise the source time is defined by the system. + * + * \param node_base_interface Node base interface. + * \param node_topics_interface Node topic base interface. + * \param node_graph_interface Node graph interface. + * \param node_services_interface Node service interface. + * \param node_logging_interface Node logging interface. + * \param node_clock_interface Node clock interface. + * \param node_parameters_interface Node parameters interface. + */ RCLCPP_PUBLIC void attachNode( rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface, @@ -54,19 +81,24 @@ class TimeSource rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_interface, rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_interface); + /// Detach the node from the tiem source RCLCPP_PUBLIC void detachNode(); /// Attach a clock to the time source to be updated /** + * The time source must be a RCL_ROS_TIME otherwise throws an exception + * * \throws std::invalid_argument if node is nullptr */ RCLCPP_PUBLIC void attachClock(rclcpp::Clock::SharedPtr clock); + /// Detach a clock to the time source RCLCPP_PUBLIC void detachClock(rclcpp::Clock::SharedPtr clock); + /// TimeSource Destuctor RCLCPP_PUBLIC ~TimeSource(); diff --git a/rclcpp/include/rclcpp/timer.hpp b/rclcpp/include/rclcpp/timer.hpp index dd754c0748..75be9061b6 100644 --- a/rclcpp/include/rclcpp/timer.hpp +++ b/rclcpp/include/rclcpp/timer.hpp @@ -48,15 +48,26 @@ class TimerBase public: RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(TimerBase) + /// TimerBase constructor + /** + * \param clock A clock to use for time and sleeping + * \param period The interval at which the timer fires + * \param context node context + */ RCLCPP_PUBLIC explicit TimerBase( Clock::SharedPtr clock, std::chrono::nanoseconds period, rclcpp::Context::SharedPtr context); + /// TimerBase destructor RCLCPP_PUBLIC ~TimerBase(); + /// Cancel the timer. + /** + * \throws std::runtime_error if the rcl_timer_cancel returns a failure + */ RCLCPP_PUBLIC void cancel(); @@ -71,10 +82,15 @@ class TimerBase bool is_canceled(); + /// Reset the timer. + /** + * \throws std::runtime_error if the rcl_timer_reset returns a failure + */ RCLCPP_PUBLIC void reset(); + /// Handles the function to execute when the timer is emit a trigger. RCLCPP_PUBLIC virtual void execute_callback() = 0; @@ -169,6 +185,10 @@ class GenericTimer : public TimerBase cancel(); } + /// Handles the function to execute when the timer is emit a trigger. + /** + * \throws std::runtime_error if the rcl_timer_call returns a failure (except cancel). + */ void execute_callback() override { @@ -209,6 +229,8 @@ class GenericTimer : public TimerBase callback_(*this); } + /// Is the clock steady (i.e. is the time between ticks constant?) + /** \return True if the clock used by this timer is steady. */ bool is_steady() override { @@ -233,6 +255,12 @@ class WallTimer : public GenericTimer public: RCLCPP_SMART_PTR_DEFINITIONS(WallTimer) + /// Wall timer constructor + /** + * \param period The interval at which the timer fires + * \param callback The callback function to execute every interval + * \param context node context + */ WallTimer( std::chrono::nanoseconds period, FunctorT && callback, From b6a109d3fcaa62545b54b299aa19ecffc2f5960b Mon Sep 17 00:00:00 2001 From: ahcorde Date: Tue, 5 May 2020 10:28:37 +0200 Subject: [PATCH 2/3] Added feedback Signed-off-by: ahcorde --- rclcpp/include/rclcpp/client.hpp | 4 +-- rclcpp/include/rclcpp/duration.hpp | 20 +++---------- rclcpp/include/rclcpp/node.hpp | 2 +- rclcpp/include/rclcpp/parameter.hpp | 30 +++++++++++++++++++ rclcpp/include/rclcpp/service.hpp | 16 +++++----- .../include/rclcpp/subscription_options.hpp | 2 +- rclcpp/include/rclcpp/time.hpp | 27 ++++++----------- rclcpp/include/rclcpp/time_source.hpp | 8 ++--- rclcpp/include/rclcpp/timer.hpp | 6 +--- 9 files changed, 59 insertions(+), 56 deletions(-) diff --git a/rclcpp/include/rclcpp/client.hpp b/rclcpp/include/rclcpp/client.hpp index 20b5d91b82..e6b02f9969 100644 --- a/rclcpp/include/rclcpp/client.hpp +++ b/rclcpp/include/rclcpp/client.hpp @@ -84,8 +84,8 @@ class ClientBase bool take_type_erased_response(void * response_out, rmw_request_id_t & request_header_out); - /// Return the name of the node. - /** \return The name of the node. */ + /// Return the name of the service. + /** \return The name of the service. */ RCLCPP_PUBLIC const char * get_service_name() const; diff --git a/rclcpp/include/rclcpp/duration.hpp b/rclcpp/include/rclcpp/duration.hpp index 115b7040ab..a3e3edeeaa 100644 --- a/rclcpp/include/rclcpp/duration.hpp +++ b/rclcpp/include/rclcpp/duration.hpp @@ -31,10 +31,10 @@ class RCLCPP_PUBLIC Duration * Initializes the time values for seconds and nanoseconds individually. * Large values for nsecs are wrapped automatically with the remainder added to secs. * Both inputs must be integers. - * Durations can be negative. + * Seconds can be negative. * * \param seconds time in seconds - * \param nanoseconds time in seconds + * \param nanoseconds time in nanoseconds */ Duration(int32_t seconds, uint32_t nanoseconds); @@ -61,60 +61,48 @@ class RCLCPP_PUBLIC Duration */ explicit Duration(const rcl_duration_t & duration); - /// Copy constructor. Duration(const Duration & rhs); - /// Duration destructor. virtual ~Duration() = default; - /// Return a builtin_interfaces::msg::Duration object based operator builtin_interfaces::msg::Duration() const; // cppcheck-suppress operatorEq // this is a false positive from cppcheck Duration & operator=(const Duration & rhs); - /// Copy assign operator from a builtin_interfaces::msg::Duration. Duration & operator=(const builtin_interfaces::msg::Duration & Duration_msg); - /// Equal operator. bool operator==(const rclcpp::Duration & rhs) const; - /// Less than operator. bool operator<(const rclcpp::Duration & rhs) const; - /// Less or equal than operator. bool operator<=(const rclcpp::Duration & rhs) const; - /// Greater or equal than operator. bool operator>=(const rclcpp::Duration & rhs) const; - /// Greater than operator. bool operator>(const rclcpp::Duration & rhs) const; - /// Addition operator. Duration operator+(const rclcpp::Duration & rhs) const; - /// Subtraction operator. Duration operator-(const rclcpp::Duration & rhs) const; - /// Get the maximum duration value. + /// Get the maximum representable value. /** - * \return the maximum duration value + * \return the maximum representable value */ static Duration max(); - /// Multiplication operator. Duration operator*(double scale) const; diff --git a/rclcpp/include/rclcpp/node.hpp b/rclcpp/include/rclcpp/node.hpp index 2b0faf97e9..7279a6a97e 100644 --- a/rclcpp/include/rclcpp/node.hpp +++ b/rclcpp/include/rclcpp/node.hpp @@ -243,7 +243,7 @@ class Node : public std::enable_shared_from_this const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default, rclcpp::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. diff --git a/rclcpp/include/rclcpp/parameter.hpp b/rclcpp/include/rclcpp/parameter.hpp index 9e56c4f8ef..68147ed731 100644 --- a/rclcpp/include/rclcpp/parameter.hpp +++ b/rclcpp/include/rclcpp/parameter.hpp @@ -109,6 +109,9 @@ class Parameter get_parameter_value() const; /// Get value of parameter using rclcpp::ParameterType as template argument. + /** + * \throws rclcpp::exceptions::InvalidParameterTypeException if the type doesn't match + */ template decltype(auto) get_value() const @@ -122,46 +125,73 @@ class Parameter get_value() const; /// Get value of parameter as boolean. + /** + * \throws rclcpp::ParameterTypeException if the type doesn't match + */ RCLCPP_PUBLIC bool as_bool() const; /// Get value of parameter as integer. + /** + * \throws rclcpp::ParameterTypeException if the type doesn't match + */ RCLCPP_PUBLIC int64_t as_int() const; /// Get value of parameter as double. + /** + * \throws rclcpp::ParameterTypeException if the type doesn't match + */ RCLCPP_PUBLIC double as_double() const; /// Get value of parameter as string. + /** + * \throws rclcpp::ParameterTypeException if the type doesn't match + */ RCLCPP_PUBLIC const std::string & as_string() const; /// Get value of parameter as byte array (vector). + /** + * \throws rclcpp::ParameterTypeException if the type doesn't match + */ RCLCPP_PUBLIC const std::vector & as_byte_array() const; /// Get value of parameter as bool array (vector). + /** + * \throws rclcpp::ParameterTypeException if the type doesn't match + */ RCLCPP_PUBLIC const std::vector & as_bool_array() const; /// Get value of parameter as integer array (vector). + /** + * \throws rclcpp::ParameterTypeException if the type doesn't match + */ RCLCPP_PUBLIC const std::vector & as_integer_array() const; /// Get value of parameter as double array (vector). + /** + * \throws rclcpp::ParameterTypeException if the type doesn't match + */ RCLCPP_PUBLIC const std::vector & as_double_array() const; /// Get value of parameter as string array (vector). + /** + * \throws rclcpp::ParameterTypeException if the type doesn't match + */ RCLCPP_PUBLIC const std::vector & as_string_array() const; diff --git a/rclcpp/include/rclcpp/service.hpp b/rclcpp/include/rclcpp/service.hpp index 6111efa09e..abe25867f0 100644 --- a/rclcpp/include/rclcpp/service.hpp +++ b/rclcpp/include/rclcpp/service.hpp @@ -50,25 +50,25 @@ class ServiceBase RCLCPP_PUBLIC virtual ~ServiceBase(); - /// Return the name of the node. - /** \return The name of the node. */ + /// Return the name of the service. + /** \return The name of the service. */ RCLCPP_PUBLIC const char * get_service_name(); - /// Return the rcl_client_t client handle in a std::shared_ptr. + /// Return the rcl_service_t service handle in a std::shared_ptr. /** - * This handle remains valid after the Client is destroyed. - * The actual rcl client is not finalized until it is out of scope everywhere. + * This handle remains valid after the Service is destroyed. + * The actual rcl service is not finalized until it is out of scope everywhere. */ RCLCPP_PUBLIC std::shared_ptr get_service_handle(); - /// Return the rcl_client_t client handle in a std::shared_ptr. + /// Return the rcl_service_t service handle in a std::shared_ptr. /** - * This handle remains valid after the Client is destroyed. - * The actual rcl client is not finalized until it is out of scope everywhere. + * This handle remains valid after the Service is destroyed. + * The actual rcl service is not finalized until it is out of scope everywhere. */ RCLCPP_PUBLIC std::shared_ptr diff --git a/rclcpp/include/rclcpp/subscription_options.hpp b/rclcpp/include/rclcpp/subscription_options.hpp index 58a6b970f6..5088f35fb1 100644 --- a/rclcpp/include/rclcpp/subscription_options.hpp +++ b/rclcpp/include/rclcpp/subscription_options.hpp @@ -90,7 +90,7 @@ struct SubscriptionOptionsWithAllocator : public SubscriptionOptionsBase /// Convert this class, with a rclcpp::QoS, into an rcl_subscription_options_t. /** - * \param qos QoS profile. + * \param qos QoS profile for subcription. * \return rcl_subscription_options_t structure based on the rclcpp::QoS */ template diff --git a/rclcpp/include/rclcpp/time.hpp b/rclcpp/include/rclcpp/time.hpp index eb247bd1b3..a80201a356 100644 --- a/rclcpp/include/rclcpp/time.hpp +++ b/rclcpp/include/rclcpp/time.hpp @@ -33,8 +33,12 @@ class Time public: /// Time constructor /** - * \param seconds since time epoch - * \param nanoseconds since time epoch + * Initializes the time values for seconds and nanoseconds individually. + * Large values for nanoseconds are wrapped automatically with the remainder added to seconds. + * Both inputs must be integers. + * + * \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 */ RCLCPP_PUBLIC @@ -78,82 +82,69 @@ class Time RCLCPP_PUBLIC operator builtin_interfaces::msg::Time() const; - /// Copy assign operator RCLCPP_PUBLIC Time & operator=(const Time & rhs); - /// Copy assign operator from a builtin_interfaces::msg::Time RCLCPP_PUBLIC Time & operator=(const builtin_interfaces::msg::Time & time_msg); - /// Equal operator. RCLCPP_PUBLIC bool operator==(const rclcpp::Time & rhs) const; - /// Not equal operator. RCLCPP_PUBLIC bool operator!=(const rclcpp::Time & rhs) const; - /// Less than operator. RCLCPP_PUBLIC bool operator<(const rclcpp::Time & rhs) const; - /// Less or equal than operator. RCLCPP_PUBLIC bool operator<=(const rclcpp::Time & rhs) const; - /// Greater or equal than operator. RCLCPP_PUBLIC bool operator>=(const rclcpp::Time & rhs) const; - /// Greater than operator. RCLCPP_PUBLIC bool operator>(const rclcpp::Time & rhs) const; - /// Addition operator with a rclcpp::Duration. RCLCPP_PUBLIC Time operator+(const rclcpp::Duration & rhs) const; - /// Subtraction operator. RCLCPP_PUBLIC Duration operator-(const rclcpp::Time & rhs) const; - /// Subtraction operator with a rclcpp::Duration. RCLCPP_PUBLIC Time operator-(const rclcpp::Duration & rhs) const; - /// Addition assigment operator with a rclcpp::Duration. RCLCPP_PUBLIC Time & operator+=(const rclcpp::Duration & rhs); - /// Subtraction assigment operator with a rclcpp::Duration. RCLCPP_PUBLIC Time & operator-=(const rclcpp::Duration & rhs); /// Get the nanoseconds since epoch /** - * \return the nanoseconds since epoch as a floating point number. + * \return the nanoseconds since epoch as a rcl_time_point_value_t structure. */ RCLCPP_PUBLIC rcl_time_point_value_t nanoseconds() const; - /// Get the maximum time value + /// Get the maximum representable value. /** - * \return the maximum time value + * \return the maximum representable value */ RCLCPP_PUBLIC static Time diff --git a/rclcpp/include/rclcpp/time_source.hpp b/rclcpp/include/rclcpp/time_source.hpp index 546ff184e4..86f62a6cab 100644 --- a/rclcpp/include/rclcpp/time_source.hpp +++ b/rclcpp/include/rclcpp/time_source.hpp @@ -81,15 +81,13 @@ class TimeSource rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_interface, rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_interface); - /// Detach the node from the tiem source + /// Detach the node from the time source RCLCPP_PUBLIC void detachNode(); /// Attach a clock to the time source to be updated /** - * The time source must be a RCL_ROS_TIME otherwise throws an exception - * - * \throws std::invalid_argument if node is nullptr + * \throws std::invalid_argument the time source must be a RCL_ROS_TIME otherwise throws an exception */ RCLCPP_PUBLIC void attachClock(rclcpp::Clock::SharedPtr clock); @@ -98,7 +96,7 @@ class TimeSource RCLCPP_PUBLIC void detachClock(rclcpp::Clock::SharedPtr clock); - /// TimeSource Destuctor + /// TimeSource Destructor RCLCPP_PUBLIC ~TimeSource(); diff --git a/rclcpp/include/rclcpp/timer.hpp b/rclcpp/include/rclcpp/timer.hpp index 75be9061b6..3f3b4d80b7 100644 --- a/rclcpp/include/rclcpp/timer.hpp +++ b/rclcpp/include/rclcpp/timer.hpp @@ -90,7 +90,7 @@ class TimerBase void reset(); - /// Handles the function to execute when the timer is emit a trigger. + /// Call the callback function when the timer signal is emitted. RCLCPP_PUBLIC virtual void execute_callback() = 0; @@ -185,10 +185,6 @@ class GenericTimer : public TimerBase cancel(); } - /// Handles the function to execute when the timer is emit a trigger. - /** - * \throws std::runtime_error if the rcl_timer_call returns a failure (except cancel). - */ void execute_callback() override { From 446eea7bf12a2f66a111fc1e13d74a65744bc29c Mon Sep 17 00:00:00 2001 From: ahcorde Date: Tue, 5 May 2020 19:36:52 +0200 Subject: [PATCH 3/3] Added feedback Signed-off-by: ahcorde --- rclcpp/include/rclcpp/duration.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rclcpp/include/rclcpp/duration.hpp b/rclcpp/include/rclcpp/duration.hpp index a3e3edeeaa..eb716c3348 100644 --- a/rclcpp/include/rclcpp/duration.hpp +++ b/rclcpp/include/rclcpp/duration.hpp @@ -126,7 +126,7 @@ class RCLCPP_PUBLIC Duration static Duration from_seconds(double seconds); - /// Convert Duration in to std::chrono. + /// Convert Duration into a std::chrono::Duration. template DurationT to_chrono() const