Program Listing for File common_nodes.hpp

Return to documentation for file (/tmp/ws/src/demos/quality_of_service_demo/rclcpp/include/quality_of_service_demo/common_nodes.hpp)

// Copyright 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved.
//
// 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 QUALITY_OF_SERVICE_DEMO__COMMON_NODES_HPP_
#define QUALITY_OF_SERVICE_DEMO__COMMON_NODES_HPP_

#include <chrono>
#include <memory>
#include <string>

#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"

constexpr char DEFAULT_TOPIC_NAME[] = "qos_chatter";

class Talker final : public rclcpp::Node
{
public:

  explicit Talker(
    const rclcpp::QoS & qos_profile,
    const std::string & topic_name = DEFAULT_TOPIC_NAME,
    size_t publish_count = 0,
    std::chrono::milliseconds publish_period = std::chrono::milliseconds(500),
    std::chrono::milliseconds assert_topic_period = std::chrono::milliseconds(0));

  void initialize();


  void publish();

  size_t get_published_count() const;

  bool assert_publisher_liveliness() const;

  void toggle_publish();


  void pause_publish_for(std::chrono::milliseconds pause_duration);

  void stop_publish_and_assert_liveliness();

  rclcpp::PublisherOptions & get_options() {return publisher_options_;}

  void print_qos() const;

private:
  rclcpp::QoS qos_profile_;
  rclcpp::PublisherOptions publisher_options_;
  rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_ = nullptr;

  const std::string topic_name_;
  size_t publish_count_ = 0;
  const size_t stop_at_count_ = 0;

  std::chrono::milliseconds publish_period_ = std::chrono::milliseconds(500);
  std::chrono::milliseconds assert_topic_period_ = std::chrono::milliseconds(0);
  rclcpp::TimerBase::SharedPtr publish_timer_ = nullptr;
  rclcpp::TimerBase::SharedPtr pause_timer_ = nullptr;
  rclcpp::TimerBase::SharedPtr assert_topic_timer_ = nullptr;
};

class Listener final : public rclcpp::Node
{
public:

  explicit Listener(
    const rclcpp::QoS & qos_profile,
    const std::string & topic_name = DEFAULT_TOPIC_NAME,
    bool defer_subscribe = false);

  void initialize();


  void start_listening();

  rclcpp::SubscriptionOptions & get_options() {return subscription_options_;}

  void print_qos() const;

private:
  rclcpp::QoS qos_profile_;
  rclcpp::SubscriptionOptions subscription_options_;
  rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscription_ = nullptr;

  const std::string topic_name_;
  const bool defer_subscribe_ = false;
};

#endif  // QUALITY_OF_SERVICE_DEMO__COMMON_NODES_HPP_