Go to the documentation of this file.
19 #ifndef LANELET2_MAP_PROVIDER__LANELET2_MAP_PROVIDER_HPP_
20 #define LANELET2_MAP_PROVIDER__LANELET2_MAP_PROVIDER_HPP_
22 #include <tf2_geometry_msgs/tf2_geometry_msgs.h>
24 #include <lanelet2_core/LaneletMap.h>
30 #include "autoware_auto_mapping_msgs/msg/had_map_bin.hpp"
61 const std::string & map_filename,
71 const std::string & map_filename,
const LatLonAlt map_frame_origin,
76 std::shared_ptr<lanelet::LaneletMap>
m_map;
83 const std::string & map_filename,
const LatLonAlt map_frame_origin);
90 #endif // LANELET2_MAP_PROVIDER__LANELET2_MAP_PROVIDER_HPP_
This file includes common type definition.
std::shared_ptr< lanelet::LaneletMap > m_map
Definition: lanelet2_map_provider.hpp:76
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
geocentric_pose_t NDT_PUBLIC load_map(const std::string &yaml_file_name, const std::string &pcl_file_name, sensor_msgs::msg::PointCloud2 &pc_out)
Read the pcd file with filename into a PointCloud2 message, transform it into an NDT representation a...
Definition: ndt_map_publisher.cpp:181
float64_t lat
latitude in degrees
Definition: lanelet2_map_provider.hpp:44
geometry_msgs::msg::TransformStamped TransformStamped
Definition: motion_testing_publisher.hpp:37
float64_t lon
longitude in degrees
Definition: lanelet2_map_provider.hpp:45
float64_t alt
altitude in meters
Definition: lanelet2_map_provider.hpp:46
Definition: lanelet2_map_provider.launch.py:1
Provides functoins to load and access a lanelet2 OSM map.
Definition: lanelet2_map_provider.hpp:51
Definition: lanelet2_map_provider.hpp:42
double float64_t
Definition: types.hpp:47