33 lines
No EOL
752 B
C++
33 lines
No EOL
752 B
C++
#pragma once
|
|
|
|
#include <string>
|
|
#include <rclcpp/rclcpp.hpp>
|
|
// #include <geometry_msgs/msg/pose.hpp>
|
|
|
|
namespace printer
|
|
{
|
|
|
|
template <class Derived>
|
|
class PrinterBase: public rclcpp::Node
|
|
{
|
|
|
|
inline const Derived& derived() const& noexcept
|
|
{
|
|
return *static_cast<const Derived*>(this);
|
|
}
|
|
|
|
public:
|
|
explicit PrinterBase(const rclcpp::NodeOptions& options);
|
|
virtual ~PrinterBase() = default;
|
|
// virtual void print(const std::string& frame_name,
|
|
// const geometry_msgs::msg::Pose& placement_pose,
|
|
// const std::string& package_name);
|
|
// virtual ~Printer();
|
|
|
|
protected:
|
|
std::string _printer_name;
|
|
// geometry_msgs::msg::Pose _printer_pose;
|
|
|
|
};
|
|
|
|
} // namespace printer
|