Program Listing for File qos.hpp

Return to documentation for file (include/rclcpp/qos.hpp)

// Copyright 2019 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
//     http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef RCLCPP__QOS_HPP_
#define RCLCPP__QOS_HPP_

#include <string>

#include "rclcpp/duration.hpp"
#include "rclcpp/exceptions.hpp"
#include "rclcpp/visibility_control.hpp"
#include "rcl/logging_rosout.h"
#include "rmw/incompatible_qos_events_statuses.h"
#include "rmw/qos_profiles.h"
#include "rmw/types.h"

namespace rclcpp
{

RCLCPP_PUBLIC
std::string qos_policy_name_from_kind(rmw_qos_policy_kind_t policy_kind);

enum class HistoryPolicy
{
  KeepLast = RMW_QOS_POLICY_HISTORY_KEEP_LAST,
  KeepAll = RMW_QOS_POLICY_HISTORY_KEEP_ALL,
  SystemDefault = RMW_QOS_POLICY_HISTORY_SYSTEM_DEFAULT,
  Unknown = RMW_QOS_POLICY_HISTORY_UNKNOWN,
};

enum class ReliabilityPolicy
{
  BestEffort = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT,
  Reliable = RMW_QOS_POLICY_RELIABILITY_RELIABLE,
  SystemDefault = RMW_QOS_POLICY_RELIABILITY_SYSTEM_DEFAULT,
  BestAvailable = RMW_QOS_POLICY_RELIABILITY_BEST_AVAILABLE,
  Unknown = RMW_QOS_POLICY_RELIABILITY_UNKNOWN,
};

enum class DurabilityPolicy
{
  Volatile = RMW_QOS_POLICY_DURABILITY_VOLATILE,
  TransientLocal = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL,
  SystemDefault = RMW_QOS_POLICY_DURABILITY_SYSTEM_DEFAULT,
  BestAvailable = RMW_QOS_POLICY_DURABILITY_BEST_AVAILABLE,
  Unknown = RMW_QOS_POLICY_DURABILITY_UNKNOWN,
};

enum class LivelinessPolicy
{
  Automatic = RMW_QOS_POLICY_LIVELINESS_AUTOMATIC,
  ManualByTopic = RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC,
  SystemDefault = RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT,
  BestAvailable = RMW_QOS_POLICY_LIVELINESS_BEST_AVAILABLE,
  Unknown = RMW_QOS_POLICY_LIVELINESS_UNKNOWN,
};

enum class QoSCompatibility
{
  Ok = RMW_QOS_COMPATIBILITY_OK,
  Warning = RMW_QOS_COMPATIBILITY_WARNING,
  Error = RMW_QOS_COMPATIBILITY_ERROR,
};

struct RCLCPP_PUBLIC QoSInitialization
{
  rmw_qos_history_policy_t history_policy;
  size_t depth;

  QoSInitialization(
    rmw_qos_history_policy_t history_policy_arg, size_t depth_arg,
    bool print_depth_warning = true);

  static
  QoSInitialization
  from_rmw(const rmw_qos_profile_t & rmw_qos);
};

struct RCLCPP_PUBLIC KeepAll : public rclcpp::QoSInitialization
{
  KeepAll();
};

struct RCLCPP_PUBLIC KeepLast : public rclcpp::QoSInitialization
{
  explicit KeepLast(size_t depth, bool print_depth_warning = true);
};


class RCLCPP_PUBLIC QoS
{
public:

  explicit
  QoS(
    const QoSInitialization & qos_initialization,
    const rmw_qos_profile_t & initial_profile = rmw_qos_profile_default);


  // cppcheck-suppress noExplicitConstructor
  QoS(size_t history_depth);  // NOLINT(runtime/explicit): conversion constructor

  rmw_qos_profile_t &
  get_rmw_qos_profile();

  const rmw_qos_profile_t &
  get_rmw_qos_profile() const;

  QoS &
  history(HistoryPolicy history);

  QoS &
  history(rmw_qos_history_policy_t history);

  QoS &
  keep_last(size_t depth);

  QoS &
  keep_all();

  QoS &
  reliability(rmw_qos_reliability_policy_t reliability);

  QoS &
  reliability(ReliabilityPolicy reliability);

  QoS &
  reliable();

  QoS &
  best_effort();

  QoS &
  reliability_best_available();

  QoS &
  durability(rmw_qos_durability_policy_t durability);

  QoS &
  durability(DurabilityPolicy durability);


  QoS &
  durability_volatile();

  QoS &
  transient_local();

  QoS &
  durability_best_available();

  QoS &
  deadline(rmw_time_t deadline);

  QoS &
  deadline(const rclcpp::Duration & deadline);

  QoS &
  lifespan(rmw_time_t lifespan);

  QoS &
  lifespan(const rclcpp::Duration & lifespan);

  QoS &
  liveliness(rmw_qos_liveliness_policy_t liveliness);

  QoS &
  liveliness(LivelinessPolicy liveliness);

  QoS &
  liveliness_lease_duration(rmw_time_t liveliness_lease_duration);

  QoS &
  liveliness_lease_duration(const rclcpp::Duration & liveliness_lease_duration);

  QoS &
  avoid_ros_namespace_conventions(bool avoid_ros_namespace_conventions);

  HistoryPolicy
  history() const;

  size_t
  depth() const;

  ReliabilityPolicy
  reliability() const;

  DurabilityPolicy
  durability() const;

  rclcpp::Duration
  deadline() const;

  rclcpp::Duration
  lifespan() const;

  LivelinessPolicy
  liveliness() const;

  rclcpp::Duration
  liveliness_lease_duration() const;

  bool
  avoid_ros_namespace_conventions() const;

private:
  rmw_qos_profile_t rmw_qos_profile_;
};

RCLCPP_PUBLIC
bool operator==(const QoS & left, const QoS & right);
RCLCPP_PUBLIC
bool operator!=(const QoS & left, const QoS & right);


struct QoSCheckCompatibleResult
{
  QoSCompatibility compatibility;


  std::string reason;
};


RCLCPP_PUBLIC
QoSCheckCompatibleResult
qos_check_compatible(const QoS & publisher_qos, const QoS & subscription_qos);

class RCLCPP_PUBLIC ClockQoS : public QoS
{
public:
  explicit
  ClockQoS(
    const QoSInitialization & qos_initialization = KeepLast(1));
};

class RCLCPP_PUBLIC SensorDataQoS : public QoS
{
public:
  explicit
  SensorDataQoS(
    const QoSInitialization & qos_initialization = (
      QoSInitialization::from_rmw(rmw_qos_profile_sensor_data)
  ));
};

class RCLCPP_PUBLIC ParametersQoS : public QoS
{
public:
  explicit
  ParametersQoS(
    const QoSInitialization & qos_initialization = (
      QoSInitialization::from_rmw(rmw_qos_profile_parameters)
  ));
};

class RCLCPP_PUBLIC ServicesQoS : public QoS
{
public:
  explicit
  ServicesQoS(
    const QoSInitialization & qos_initialization = (
      QoSInitialization::from_rmw(rmw_qos_profile_services_default)
  ));
};

class RCLCPP_PUBLIC ParameterEventsQoS : public QoS
{
public:
  explicit
  ParameterEventsQoS(
    const QoSInitialization & qos_initialization = (
      QoSInitialization::from_rmw(rmw_qos_profile_parameter_events)
  ));
};

class RCLCPP_PUBLIC RosoutQoS : public QoS
{
public:
  explicit
  RosoutQoS(
    const QoSInitialization & rosout_qos_initialization = (
      QoSInitialization::from_rmw(rcl_qos_profile_rosout_default)
  ));
};

class RCLCPP_PUBLIC SystemDefaultsQoS : public QoS
{
public:
  explicit
  SystemDefaultsQoS(
    const QoSInitialization & qos_initialization = (
      QoSInitialization::from_rmw(rmw_qos_profile_system_default)
  ));
};

class RCLCPP_PUBLIC BestAvailableQoS : public QoS
{
public:
  explicit
  BestAvailableQoS(
    const QoSInitialization & qos_initialization = (
      QoSInitialization::from_rmw(rmw_qos_profile_best_available)
  ));
};

}  // namespace rclcpp

#endif  // RCLCPP__QOS_HPP_