Program Listing for File twist_publisher.hpp

Return to documentation for file (include/turtlebot3_node/twist_publisher.hpp)

// Copyright (C) 2023 Ryan Friedman
//
// 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 TURTLEBOT3_NODE__TWIST_PUBLISHER_HPP_
#define TURTLEBOT3_NODE__TWIST_PUBLISHER_HPP_


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

#include "geometry_msgs/msg/twist.hpp"
#include "geometry_msgs/msg/twist_stamped.hpp"
#include "rclcpp/parameter_service.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp/qos.hpp"

class TwistPublisher
{
public:
  explicit TwistPublisher(
    const rclcpp::Node::SharedPtr & node,
    const std::string & topic,
    const rclcpp::QoS & qos)
  : topic_(topic)
  {
    if (!node->has_parameter("enable_stamped_cmd_vel")) {
      node->declare_parameter("enable_stamped_cmd_vel", false);
    }
    node->get_parameter("enable_stamped_cmd_vel", is_stamped_);

    if (is_stamped_) {
      twist_stamped_pub_ = node->create_publisher<geometry_msgs::msg::TwistStamped>(topic_, qos);
    } else {
      twist_pub_ = node->create_publisher<geometry_msgs::msg::Twist>(topic_, qos);
    }
  }

  void publish(std::unique_ptr<geometry_msgs::msg::TwistStamped> velocity)
  {
    if (is_stamped_) {
      twist_stamped_pub_->publish(std::move(velocity));
    } else {
      auto twist_msg = std::make_unique<geometry_msgs::msg::Twist>(velocity->twist);
      twist_pub_->publish(std::move(twist_msg));
    }
  }

  [[nodiscard]] size_t get_subscription_count() const
  {
    if (is_stamped_) {
      return twist_stamped_pub_->get_subscription_count();
    } else {
      return twist_pub_->get_subscription_count();
    }
  }

protected:
  std::string topic_;
  bool is_stamped_{false};
  rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr twist_pub_;
  rclcpp::Publisher<geometry_msgs::msg::TwistStamped>::SharedPtr twist_stamped_pub_;
};

#endif  // TURTLEBOT3_NODE__TWIST_PUBLISHER_HPP_