Skip to content

Commit

Permalink
PR Review suggestions
Browse files Browse the repository at this point in the history
Co-authored-by: William Woodall <william+github@osrfoundation.org>
Signed-off-by: Nikolai Morin <nikolai.morin@apex.ai>
  • Loading branch information
nnmm and wjwwood committed Jan 7, 2021
1 parent edd00ee commit 66dbc2f
Showing 1 changed file with 20 additions and 12 deletions.
32 changes: 20 additions & 12 deletions rclcpp/include/rclcpp/qos.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -91,22 +91,30 @@ struct RCLCPP_PUBLIC KeepLast : public rclcpp::QoSInitialization

/// Encapsulation of Quality of Service settings.
/**
* Quality of Service settings contains parameters for the underlying middleware, typically DDS,
* to tune communication between nodes. See
* <a href="https://index.ros.org/doc/ros2/Concepts/About-Quality-of-Service-Settings/">
About Quality of Service Settings</a> for an explanation.
* Quality of Service settings control the behavior of publishers, subscriptions,
* and other entities, and includes things like how data is sent or resent,
* how data is buffered on the publishing and subscribing side, and other things.
* See:
* <a href="https://index.ros.org/doc/ros2/Concepts/About-Quality-of-Service-Settings">
* https://index.ros.org/doc/ros2/Concepts/About-Quality-of-Service-Settings
* </a>
*/
class RCLCPP_PUBLIC QoS
{
public:
/// Constructor which allows creating a QoS by specifying only the history policy and history depth.
/**
* When using the default initial profile, this uses \link rclcpp::ReliabilityPolicy::Reliable
* ReliabilityPolicy::Reliable\endlink and \link rclcpp::DurabilityPolicy::Volatile
* DurabilityPolicy::Volatile\endlink. See the global variable rmw_qos_profile_default for a full list.
* When using the default initial profile, the defaults will include:
*
* - \link rclcpp::ReliabilityPolicy::Reliable ReliabilityPolicy::Reliable\endlink
* - \link rclcpp::DurabilityPolicy::Volatile DurabilityPolicy::Volatile\endlink
*
* See rmw_qos_profile_default for a full list of default settings.
* If some other rmw_qos_profile_t is passed to initial_profile, then the defaults will derive from
* that profile instead.
*
* \param[in] qos_initialization Specifies history policy and history depth.
* \param[in] initial_profile Specifies other settings.
* \param[in] initial_profile The rmw_qos_profile_t instance on which to base the default settings.
*/
explicit
QoS(
Expand All @@ -115,11 +123,11 @@ class RCLCPP_PUBLIC QoS

/// Conversion constructor to ease construction in the common case of just specifying depth.
/**
* This is a convenience constructor that calls
* QoS(const QoSInitialization&, const rmw_qos_profile_t &) with the first argument set
* to KeepLast(history_depth) and the second argument equal to the default.
* This is a convenience constructor that calls QoS(KeepLast(history_depth)).
*
* \param[in] history_depth How many messages can be queued up by the node.
* \param[in] history_depth How many messages can be queued when publishing
* with a Publisher, or how many messages can be queued before being replaced
* by a Subscription.
*/
// cppcheck-suppress noExplicitConstructor
QoS(size_t history_depth); // NOLINT(runtime/explicit): conversion constructor
Expand Down

0 comments on commit 66dbc2f

Please sign in to comment.