Program Listing for File publisher.hpp

Return to documentation for file (/tmp/ws/src/diagnostics/diagnostic_updater/include/diagnostic_updater/publisher.hpp)

/*********************************************************************
 * Software License Agreement (BSD License)
 *
 *  Copyright (c) 2009, Willow Garage, Inc.
 *  All rights reserved.
 *
 *  Redistribution and use in source and binary forms, with or without
 *  modification, are permitted provided that the following conditions
 *  are met:
 *
 *   * Redistributions of source code must retain the above copyright
 *     notice, this list of conditions and the following disclaimer.
 *   * Redistributions in binary form must reproduce the above
 *     copyright notice, this list of conditions and the following
 *     disclaimer in the documentation and/or other materials provided
 *     with the distribution.
 *   * Neither the name of the Willow Garage nor the names of its
 *     contributors may be used to endorse or promote products derived
 *     from this software without specific prior written permission.
 *
 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
 *  POSSIBILITY OF SUCH DAMAGE.
 *********************************************************************/

// Author: Blaise Gassend
#ifndef DIAGNOSTIC_UPDATER__PUBLISHER_HPP_
#define DIAGNOSTIC_UPDATER__PUBLISHER_HPP_

#include <memory>
#include <string>
#include <utility>

#include "diagnostic_msgs/msg/diagnostic_array.hpp"
#include "diagnostic_updater/update_functions.hpp"

#include "rclcpp/clock.hpp"
#include "rclcpp/publisher.hpp"
#include "rclcpp/subscription.hpp"

namespace
{
template<typename T, typename = void>
struct has_header : public std::false_type
{};

template<typename T>
struct has_header<T,
  typename std::enable_if<std::is_same<std_msgs::msg::Header,
  decltype(std::declval<T>().header)>::value>::type>
  : public std::true_type
{};
}  // namespace

namespace diagnostic_updater
{

class HeaderlessTopicDiagnostic : public CompositeDiagnosticTask
{
public:
  HeaderlessTopicDiagnostic(
    std::string name, diagnostic_updater::Updater & diag,
    const diagnostic_updater::FrequencyStatusParam & freq,
    const rclcpp::Clock::SharedPtr & clock = std::make_shared<rclcpp::Clock>())
  : CompositeDiagnosticTask(name + " topic status"), freq_(freq, clock)
  {
    addTask(&freq_);
    diag.add(*this);
  }

  virtual ~HeaderlessTopicDiagnostic() {}

  virtual void tick() {freq_.tick();}

  virtual void clear_window() {freq_.clear();}

private:
  diagnostic_updater::FrequencyStatus freq_;
};

class TopicDiagnostic : public HeaderlessTopicDiagnostic
{
public:
  TopicDiagnostic(
    std::string name, diagnostic_updater::Updater & diag,
    const diagnostic_updater::FrequencyStatusParam & freq,
    const diagnostic_updater::TimeStampStatusParam & stamp,
    const rclcpp::Clock::SharedPtr & clock = std::make_shared<rclcpp::Clock>())
  : HeaderlessTopicDiagnostic(name, diag, freq, clock),
    stamp_(stamp, clock),
    error_logger_(rclcpp::get_logger("TopicDiagnostic_error_logger"))
  {
    addTask(&stamp_);
  }

  virtual ~TopicDiagnostic() {}

  virtual void tick()
  {
    std::string error_msg = "tick(void) has been called on a TopicDiagnostic.";
    error_msg += " This is never correct. Use tick(rclcpp::Time &) instead.";
    RCLCPP_FATAL(error_logger_, "%s", error_msg.c_str());
  }

  virtual void tick(const rclcpp::Time & stamp)
  {
    stamp_.tick(stamp);
    HeaderlessTopicDiagnostic::tick();
  }

private:
  TimeStampStatus stamp_;
  rclcpp::Logger error_logger_;
};

template<typename MessageT, typename AllocatorT = std::allocator<void>>
class DiagnosedPublisher : public TopicDiagnostic
{
public:
  using PublisherT = rclcpp::Publisher<MessageT, AllocatorT>;

  DiagnosedPublisher(
    const typename PublisherT::SharedPtr & pub,
    diagnostic_updater::Updater & diag,
    const diagnostic_updater::FrequencyStatusParam & freq,
    const diagnostic_updater::TimeStampStatusParam & stamp)
  : TopicDiagnostic(pub->get_topic_name(), diag, freq, stamp),
    publisher_(pub)
  {
    static_assert(has_header<MessageT>::value, "Message type has to have a header.");
  }

  virtual ~DiagnosedPublisher() {}

  virtual void publish(typename PublisherT::MessageUniquePtr message)
  {
    tick(message->header.stamp);
    publisher_->publish(std::move(message));
  }

  virtual void publish(const MessageT & message)
  {
    tick(message.header.stamp);
    publisher_->publish(message);
  }

  typename PublisherT::SharedPtr
  getPublisher() const
  {
    return publisher_;
  }

  void setPublisher(typename PublisherT::SharedPtr pub)
  {
    publisher_ = pub;
  }

private:
  typename PublisherT::SharedPtr publisher_;
};
}   // namespace diagnostic_updater

#endif  // DIAGNOSTIC_UPDATER__PUBLISHER_HPP_