Autoware.Auto
ndt_map_publisher.hpp
Go to the documentation of this file.
1 // Copyright 2020 the Autoware Foundation
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 //    http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 //
15 // Co-developed by Tier IV, Inc. and Apex.AI, Inc.
16 
17 #ifndef NDT__NDT_MAP_PUBLISHER_HPP_
18 #define NDT__NDT_MAP_PUBLISHER_HPP_
19 
20 #include <ndt/ndt_map.hpp>
22 #include <sensor_msgs/msg/point_cloud2.hpp>
24 
25 #include <string>
26 
28 
29 namespace autoware
30 {
31 namespace localization
32 {
33 namespace ndt
34 {
35 
40 {
47 };
48 
53 {
60 };
61 
65 void NDT_PUBLIC read_from_yaml(
66  const std::string & yaml_file_name,
67  geodetic_pose_t * geo_pose);
68 
74 void NDT_PUBLIC read_from_pcd(
75  const std::string & file_name,
77 
86 geocentric_pose_t NDT_PUBLIC load_map(
87  const std::string & yaml_file_name,
88  const std::string & pcl_file_name,
90 } // namespace ndt
91 } // namespace localization
92 } // namespace autoware
93 
94 #endif // NDT__NDT_MAP_PUBLISHER_HPP_
autoware::localization::ndt::geocentric_pose_t::yaw
float64_t yaw
Definition: ndt_map_publisher.hpp:59
autoware::localization::ndt::geocentric_pose_t::z
float64_t z
Definition: ndt_map_publisher.hpp:56
autoware::localization::ndt::read_from_yaml
void NDT_PUBLIC read_from_yaml(const std::string &yaml_file_name, geodetic_pose_t *geo_pose)
Definition: ndt_map_publisher.cpp:35
autoware::localization::ndt::geocentric_pose_t::pitch
float64_t pitch
Definition: ndt_map_publisher.hpp:58
autoware::localization::ndt::geocentric_pose_t::x
float64_t x
Definition: ndt_map_publisher.hpp:54
autoware::localization::ndt::geodetic_pose_t::latitude
float64_t latitude
Definition: ndt_map_publisher.hpp:41
autoware::localization::ndt::geodetic_pose_t::pitch
float64_t pitch
Definition: ndt_map_publisher.hpp:45
autoware::localization::ndt::geodetic_pose_t
Definition: ndt_map_publisher.hpp:39
voxel_cloud_centroid.hpp
This file defines an instance of the VoxelCloudBase interface.
autoware::localization::ndt::read_from_pcd
void NDT_PUBLIC read_from_pcd(const std::string &file_name, sensor_msgs::msg::PointCloud2 *msg)
Definition: ndt_map_publisher.cpp:71
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::localization::ndt::load_map
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
autoware::localization::ndt::geodetic_pose_t::elevation
float64_t elevation
Definition: ndt_map_publisher.hpp:43
autoware::localization::ndt::geocentric_pose_t::roll
float64_t roll
Definition: ndt_map_publisher.hpp:57
autoware::localization::ndt::geocentric_pose_t::y
float64_t y
Definition: ndt_map_publisher.hpp:55
autoware::localization::ndt::geocentric_pose_t
Definition: ndt_map_publisher.hpp:52
autoware::localization::ndt::geodetic_pose_t::longitude
float64_t longitude
Definition: ndt_map_publisher.hpp:42
visibility_control.hpp
ndt_map.hpp
autoware::common::types::float64_t
double float64_t
Definition: types.hpp:47
autoware::localization::ndt::geodetic_pose_t::roll
float64_t roll
Definition: ndt_map_publisher.hpp:44
autoware::perception::filters::filter_node_base::PointCloud2
sensor_msgs::msg::PointCloud2 PointCloud2
Definition: filter_node_base.cpp:32
autoware::localization::ndt::geodetic_pose_t::yaw
float64_t yaw
Definition: ndt_map_publisher.hpp:46