Program Listing for File qos.hpp

Return to documentation for file (/tmp/ws/src/gazebo_ros_pkgs/gazebo_ros/include/gazebo_ros/qos.hpp)

// Copyright 2020 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 GAZEBO_ROS__QOS_HPP_
#define GAZEBO_ROS__QOS_HPP_

#include <sdf/sdf.hh>

#include <rclcpp/node_options.hpp>
#include <rclcpp/qos.hpp>

#include <gazebo_ros/node_visibility_control.h>

#include <map>
#include <memory>
#include <stdexcept>
#include <string>

namespace gazebo_ros
{

class InvalidQoSException : public std::runtime_error
{
public:
  explicit InvalidQoSException(const std::string & msg)
  : std::runtime_error(msg)
  {}
};

// Forward declare private implementation
struct QoSPrivate;


class GAZEBO_ROS_NODE_PUBLIC_TYPE QoS
{
public:
  QoS();


  QoS(
    sdf::ElementPtr _sdf,
    const std::string node_name,
    const std::string node_namespace,
    const rclcpp::NodeOptions & options);

  /*
   * \param[in] topic: Get QoS for publishers on this topic name.
   * \param[in] default_qos: The default quality of service used for settings that have not been
   *   overridden.
   */
  rclcpp::QoS get_publisher_qos(
    const std::string topic, rclcpp::QoS default_qos = rclcpp::QoS(10)) const;

  /*
   * \param[in] topic: Get QoS for subscriptions on this topic name.
   * \param[in] default_qos: The default quality of service used for settings that have not been
   *   overridden.
   */
  rclcpp::QoS get_subscription_qos(
    const std::string topic, rclcpp::QoS default_qos = rclcpp::QoS(10)) const;

  // need explicit copy constructor due to `std::unique_ptr` `impl_`
  QoS(const QoS & other);

  // this is needed due to rule of five
  QoS(QoS && other);

  // need explicit copy assignment due to `std::unique_ptr` `impl_`
  QoS & operator=(const QoS & other);

  // this is needed due to rule of five
  QoS & operator=(QoS && other);

  // this is needed due to rule of five
  ~QoS();

private:
  std::unique_ptr<QoSPrivate> impl_;
};

}  // namespace gazebo_ros
#endif  // GAZEBO_ROS__QOS_HPP_