17 #ifndef NDT_NODES__MAP_PUBLISHER_HPP_
18 #define NDT_NODES__MAP_PUBLISHER_HPP_
22 #include <sensor_msgs/msg/point_cloud2.hpp>
24 #include <tf2_geometry_msgs/tf2_geometry_msgs.h>
25 #include <tf2_msgs/msg/tf_message.hpp>
26 #include <tf2_ros/static_transform_broadcaster.h>
37 namespace localization
53 const rclcpp::NodeOptions & node_options
71 const std::string & map_frame,
72 const std::string & map_topic,
73 const std::string & viz_map_topic);
87 rclcpp::Publisher<tf2_msgs::msg::TFMessage>::SharedPtr m_pub_earth_map;
88 rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr m_pub;
89 std::unique_ptr<ndt::DynamicNDTMap> m_ndt_map_ptr;
93 const std::string m_pcl_file_name;
94 const std::string m_yaml_file_name;
96 rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr m_viz_pub;
97 std::unique_ptr<MapConfig> m_map_config_ptr;
98 std::unique_ptr<MapConfig> m_viz_map_config_ptr;
99 std::unique_ptr<VoxelGrid> m_voxelgrid_ptr;
101 rclcpp::TimerBase::SharedPtr m_visualization_timer{
nullptr};
102 rclcpp::TimerBase::SharedPtr m_transform_pub_timer{
nullptr};
109 #endif // NDT_NODES__MAP_PUBLISHER_HPP_