Simulation environment state monitor node added for detect models placement without sensors

This commit is contained in:
Roman Andrianov 2022-03-11 16:36:05 +00:00 committed by Igor Brylyov
parent 4eb6b0cd75
commit 89562336f6
76 changed files with 1985 additions and 3560 deletions

View file

@ -0,0 +1,33 @@
#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