Go to the documentation of this file.
17 #ifndef NDT__NDT_MAP_PUBLISHER_HPP_
18 #define NDT__NDT_MAP_PUBLISHER_HPP_
22 #include <sensor_msgs/msg/point_cloud2.hpp>
31 namespace localization
66 const std::string & yaml_file_name,
75 const std::string & file_name,
76 sensor_msgs::msg::PointCloud2 * msg);
84 sensor_msgs::msg::PointCloud2 & map_pc,
85 sensor_msgs::msg::PointCloud2 & source_pc);
93 geocentric_pose_t load_map(
const std::string & yaml_file_name,
const std::string & pcl_file_name);
102 void reset_pc_msg(sensor_msgs::msg::PointCloud2 & msg);
106 sensor_msgs::msg::PointCloud2 & m_map_pc;
107 sensor_msgs::msg::PointCloud2 & m_source_pc;
114 #endif // NDT__NDT_MAP_PUBLISHER_HPP_
float64_t yaw
Definition: ndt_map_publisher.hpp:59
float64_t z
Definition: ndt_map_publisher.hpp:56
void NDT_PUBLIC read_from_yaml(const std::string &yaml_file_name, geodetic_pose_t *geo_pose)
Definition: ndt_map_publisher.cpp:33
float64_t pitch
Definition: ndt_map_publisher.hpp:58
float64_t x
Definition: ndt_map_publisher.hpp:54
float64_t latitude
Definition: ndt_map_publisher.hpp:41
float64_t pitch
Definition: ndt_map_publisher.hpp:45
Definition: ndt_map_publisher.hpp:39
This file defines an instance of the VoxelCloudBase interface.
void NDT_PUBLIC read_from_pcd(const std::string &file_name, sensor_msgs::msg::PointCloud2 *msg)
Definition: ndt_map_publisher.cpp:69
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
float64_t elevation
Definition: ndt_map_publisher.hpp:43
Definition: ndt_map.hpp:219
float64_t roll
Definition: ndt_map_publisher.hpp:57
float64_t y
Definition: ndt_map_publisher.hpp:55
A configuration class for the VoxelGrid data structure, also includes some helper functionality for c...
Definition: perception/filters/voxel_grid/include/voxel_grid/config.hpp:52
Definition: ndt_map_publisher.hpp:52
float64_t longitude
Definition: ndt_map_publisher.hpp:42
double float64_t
Definition: types.hpp:37
Definition: ndt_map_publisher.hpp:78
float64_t roll
Definition: ndt_map_publisher.hpp:44
float64_t yaw
Definition: ndt_map_publisher.hpp:46