Program Listing for File topic_bridge_options.hpp
↰ Return to documentation for file (include/domain_bridge/topic_bridge_options.hpp)
// Copyright 2021, 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 DOMAIN_BRIDGE__TOPIC_BRIDGE_OPTIONS_HPP_
#define DOMAIN_BRIDGE__TOPIC_BRIDGE_OPTIONS_HPP_
#include <memory>
#include <string>
#include "rclcpp/callback_group.hpp"
#include "domain_bridge/qos_options.hpp"
#include "domain_bridge/visibility_control.hpp"
namespace domain_bridge
{
class TopicBridgeOptions
{
public:
  DOMAIN_BRIDGE_PUBLIC
  TopicBridgeOptions() = default;
  DOMAIN_BRIDGE_PUBLIC
  std::shared_ptr<rclcpp::CallbackGroup>
  callback_group() const;
  DOMAIN_BRIDGE_PUBLIC
  TopicBridgeOptions &
  callback_group(std::shared_ptr<rclcpp::CallbackGroup> group);
  DOMAIN_BRIDGE_PUBLIC
  QosOptions
  qos_options() const;
  DOMAIN_BRIDGE_PUBLIC
  TopicBridgeOptions &
  qos_options(const QosOptions & qos_options);
  DOMAIN_BRIDGE_PUBLIC
  const std::string &
  remap_name() const;
  DOMAIN_BRIDGE_PUBLIC
  TopicBridgeOptions &
  remap_name(const std::string & remap_name);
  DOMAIN_BRIDGE_PUBLIC
  const bool &
  bidirectional() const;
  DOMAIN_BRIDGE_PUBLIC
  TopicBridgeOptions &
  bidirectional(const bool & bidirectional);
  DOMAIN_BRIDGE_PUBLIC
  const bool &
  reversed() const;
  DOMAIN_BRIDGE_PUBLIC
  TopicBridgeOptions &
  reversed(const bool & reversed);
  DOMAIN_BRIDGE_PUBLIC
  const std::chrono::milliseconds &
  delay() const;
  DOMAIN_BRIDGE_PUBLIC
  TopicBridgeOptions &
  delay(const std::chrono::milliseconds & delay);
  DOMAIN_BRIDGE_PUBLIC
  TopicBridgeOptions &
  wait_for_subscription(bool value);
  DOMAIN_BRIDGE_PUBLIC
  bool
  wait_for_subscription() const;
  DOMAIN_BRIDGE_PUBLIC
  TopicBridgeOptions &
  wait_for_publisher(bool value);
  DOMAIN_BRIDGE_PUBLIC
  bool
  wait_for_publisher() const;
  enum class AutoRemove
  {
    OnNoPublisher,
    OnNoSubscription,
    OnNoPublisherOrSubscription,
    Disabled,
  };
  DOMAIN_BRIDGE_PUBLIC
  TopicBridgeOptions &
  auto_remove(AutoRemove value);
  DOMAIN_BRIDGE_PUBLIC
  AutoRemove
  auto_remove() const;
private:
  std::shared_ptr<rclcpp::CallbackGroup> callback_group_{nullptr};
  QosOptions qos_options_;
  std::string remap_name_;
  bool bidirectional_{false};
  bool reversed_{false};
  bool wait_for_subscription_{false};
  bool wait_for_publisher_{true};
  AutoRemove auto_remove_{AutoRemove::Disabled};
  std::chrono::milliseconds delay_{0};
};  // class TopicBridgeOptions
}  // namespace domain_bridge
#endif  // DOMAIN_BRIDGE__TOPIC_BRIDGE_OPTIONS_HPP_