diff --git a/LICENSE b/LICENSE new file mode 100644 index 0000000..2adbd64 --- /dev/null +++ b/LICENSE @@ -0,0 +1,194 @@ + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + + +This project licensed as follows + + Copyright 2020 daohu527 + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. diff --git a/README.md b/README.md index df43336..a156615 100644 --- a/README.md +++ b/README.md @@ -1,2 +1,87 @@ # OpenHDMap -An open HD map production process for autonomous car simulation +This is an open source HD map project for autonomous driving. The precision map production process is divided into four parts: **map collection, map production, map labeling, and map saving**. This project mainly uses lidar as a collection sensor to provide the map making process, map labeling tool, and map save format. + +The goal is to provide a complete mapping process for autonomous driving. + +If you have any advice, please feel free to contact [daohu527@gmail.com]() + +## Introduce +Let ’s start with how to make an HD map. The HD map making process can be divided into 4 steps. +1. Map collection +2. Map production +3. Map labeling +4. Map saving + +Next we introduce these four processes respectively. +![HDmap_pipeline](docs/img/hdmap_pipeline.jpg) + +#### 1. Map collection +First, we use a map collection car equipped with lidar, camera, GPS and IMU to collect maps. The data currently used is an open source dataset. We plan to provide recommended hardware and toy cars later. + +You can use the collected data set or equip your own sensors to collect data. +* Collected dataset: KITTI +* Recommended equipment: todo (If you have good suggestions, welcome to recommend) + +#### 2. Map production +Then, We need to generate street and building models based on the collected point cloud data. The production process is the stitching of point clouds. This process is often referred to as point cloud registration. After stitching the point clouds frame by frame, a three-dimensional model of the entire street is obtained. You scanned the whole earth with lidar. it looks really cool, right? + +There are currently two methods to generate point cloud maps, one is through NDT Mapping, and the other is offline SLAM mapping. At present, we choose to use NDT Mapping. Here we refer to the implementation of autoware. + +There are several SLAM mapping methods to refer to: +* LOAM +* Cartographer +* hdl_graph_slam +* blam +* A-LOAM +* LeGO-LOAM +* LIO-mapping +* interactive_slam + +> We will use the above method to build the map later. + +#### 3. Map labeling +After you have completed the 3D model of the map, this part of the map is called a point cloud map. To get lane line, traffic lights and traffic sign information, we also need to label the map. At present, labeling is mainly done manually. We will provide labeling tools. The labeled map is called HD map. + +The two most important questions in map labels are as follows. +* **Sensor fusion** - Because the resolution of the point cloud is not high, the purpose of sensor fusion is to map the pictures of the camera to the point cloud to improve the resolution of lane lines and traffic signs. +* **Automatic labeling** - Automatic labeling capability for large-scale map production and maintenance. + +At present, we adopt the method of manual annotation, and we will gradually solve the above two problems later. + + +#### 4. Map saving +The preservation of HD maps is divided into two parts, one is the format of the map, and the other is the layers of the map. +* Map format +The format of the map is currently opendrive. In short, the project hopes to have a unified labeling format. + +- Map layers +Map is divided into 3 layers: base layer, positioning layer and dynamic layer. + - Base layer. The basic layer is the structured information of the map generated by the above annotations, including lane lines, traffic rule information, etc. + - Positioning layer. The positioning layer is some original point clouds that are helpful for autonomous driving positioning, such as telephone poles, traffic signs, buildings, etc. + - Dynamic layer. The dynamic layer publishes some dynamically changing information, such as traffic conditions, traffic accidents ahead, etc. + +We currently use Apollo HD map format to work with simulator to verify HD maps. + +## Quick start + +#### 1. Map production +We use "Autoware NDT Mapping" to build a small map from open dataset. The code is reference in "core_perception/lidar_localizer/nodes/ndt_mapping" [Link](https://gitlab.com/autowarefoundation/autoware.ai/core_perception). The code is now in dir "map_production". + +#### 2. Map labeling +We will soon release a map annotation tool, which will in "map_labeling" dir. + +#### 3. How to build + +## Examples + +## Benchmark +Benchmark of the process: +* accurate +* time + +## Reference +[vector tiles](https://docs.mapbox.com/vector-tiles/reference/) +[awesome-vector-tiles](https://github.com/mapbox/awesome-vector-tiles) +[paperjs](http://paperjs.org/examples/hit-testing/) +[best-javascript-drawing-libraries](https://www.slant.co/topics/28/~best-javascript-drawing-libraries) + diff --git a/docs/img/Architecture.jpg b/docs/img/Architecture.jpg new file mode 100644 index 0000000..f1b0eb0 Binary files /dev/null and b/docs/img/Architecture.jpg differ diff --git a/docs/img/Layers.jpg b/docs/img/Layers.jpg new file mode 100644 index 0000000..50fa77b Binary files /dev/null and b/docs/img/Layers.jpg differ diff --git a/docs/img/hdmap_pipeline.jpg b/docs/img/hdmap_pipeline.jpg new file mode 100644 index 0000000..d97b801 Binary files /dev/null and b/docs/img/hdmap_pipeline.jpg differ diff --git a/docs/img/map_edit.jpg b/docs/img/map_edit.jpg new file mode 100644 index 0000000..2e9b19d Binary files /dev/null and b/docs/img/map_edit.jpg differ diff --git a/map_production/ndt_mapping/ndt_mapping.cpp b/map_production/ndt_mapping/ndt_mapping.cpp new file mode 100644 index 0000000..2e2ec66 --- /dev/null +++ b/map_production/ndt_mapping/ndt_mapping.cpp @@ -0,0 +1,1048 @@ +/* + * Copyright 2015-2019 Autoware Foundation. All rights reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/* + Localization and mapping program using Normal Distributions Transform + + Yuki KITSUKAWA + */ + +#define OUTPUT // If you want to output "position_log.txt", "#define OUTPUT". + +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include + +#include +#include +#ifdef CUDA_FOUND +#include +#endif +#ifdef USE_PCL_OPENMP +#include +#endif + +#include +#include + +#include + +struct pose +{ + double x; + double y; + double z; + double roll; + double pitch; + double yaw; +}; + +enum class MethodType +{ + PCL_GENERIC = 0, + PCL_ANH = 1, + PCL_ANH_GPU = 2, + PCL_OPENMP = 3, +}; +static MethodType _method_type = MethodType::PCL_GENERIC; + +// global variables +static pose previous_pose, guess_pose, guess_pose_imu, guess_pose_odom, guess_pose_imu_odom, current_pose, + current_pose_imu, current_pose_odom, current_pose_imu_odom, ndt_pose, added_pose, localizer_pose; + +static ros::Time current_scan_time; +static ros::Time previous_scan_time; +static ros::Duration scan_duration; + +static double diff = 0.0; +static double diff_x = 0.0, diff_y = 0.0, diff_z = 0.0, diff_yaw; // current_pose - previous_pose +static double offset_imu_x, offset_imu_y, offset_imu_z, offset_imu_roll, offset_imu_pitch, offset_imu_yaw; +static double offset_odom_x, offset_odom_y, offset_odom_z, offset_odom_roll, offset_odom_pitch, offset_odom_yaw; +static double offset_imu_odom_x, offset_imu_odom_y, offset_imu_odom_z, offset_imu_odom_roll, offset_imu_odom_pitch, + offset_imu_odom_yaw; + +static double current_velocity_x = 0.0; +static double current_velocity_y = 0.0; +static double current_velocity_z = 0.0; + +static double current_velocity_imu_x = 0.0; +static double current_velocity_imu_y = 0.0; +static double current_velocity_imu_z = 0.0; + +static pcl::PointCloud map; + +static pcl::NormalDistributionsTransform ndt; +static cpu::NormalDistributionsTransform anh_ndt; +#ifdef CUDA_FOUND +static gpu::GNormalDistributionsTransform anh_gpu_ndt; +#endif +#ifdef USE_PCL_OPENMP +static pcl_omp::NormalDistributionsTransform omp_ndt; +#endif + +// Default values +static int max_iter = 30; // Maximum iterations +static float ndt_res = 1.0; // Resolution +static double step_size = 0.1; // Step size +static double trans_eps = 0.01; // Transformation epsilon + +// Leaf size of VoxelGrid filter. +static double voxel_leaf_size = 2.0; + +static ros::Time callback_start, callback_end, t1_start, t1_end, t2_start, t2_end, t3_start, t3_end, t4_start, t4_end, + t5_start, t5_end; +static ros::Duration d_callback, d1, d2, d3, d4, d5; + +static ros::Publisher ndt_map_pub; +static ros::Publisher current_pose_pub; +static ros::Publisher guess_pose_linaer_pub; +static geometry_msgs::PoseStamped current_pose_msg, guess_pose_msg; + +static ros::Publisher ndt_stat_pub; +static std_msgs::Bool ndt_stat_msg; + +static int initial_scan_loaded = 0; + +static Eigen::Matrix4f gnss_transform = Eigen::Matrix4f::Identity(); + +static double min_scan_range = 5.0; +static double max_scan_range = 200.0; +static double min_add_scan_shift = 1.0; + +static double _tf_x, _tf_y, _tf_z, _tf_roll, _tf_pitch, _tf_yaw; +static Eigen::Matrix4f tf_btol, tf_ltob; + +static bool _use_imu = false; +static bool _use_odom = false; +static bool _imu_upside_down = false; + +static bool _incremental_voxel_update = false; + +static std::string _imu_topic = "/imu_raw"; + +static double fitness_score; +static bool has_converged; +static int final_num_iteration; +static double transformation_probability; + +static sensor_msgs::Imu imu; +static nav_msgs::Odometry odom; + +static std::ofstream ofs; +static std::string filename; + +static void param_callback(const autoware_config_msgs::ConfigNDTMapping::ConstPtr& input) +{ + ndt_res = input->resolution; + step_size = input->step_size; + trans_eps = input->trans_epsilon; + max_iter = input->max_iterations; + voxel_leaf_size = input->leaf_size; + min_scan_range = input->min_scan_range; + max_scan_range = input->max_scan_range; + min_add_scan_shift = input->min_add_scan_shift; + + std::cout << "param_callback" << std::endl; + std::cout << "ndt_res: " << ndt_res << std::endl; + std::cout << "step_size: " << step_size << std::endl; + std::cout << "trans_epsilon: " << trans_eps << std::endl; + std::cout << "max_iter: " << max_iter << std::endl; + std::cout << "voxel_leaf_size: " << voxel_leaf_size << std::endl; + std::cout << "min_scan_range: " << min_scan_range << std::endl; + std::cout << "max_scan_range: " << max_scan_range << std::endl; + std::cout << "min_add_scan_shift: " << min_add_scan_shift << std::endl; +} + +static void output_callback(const autoware_config_msgs::ConfigNDTMappingOutput::ConstPtr& input) +{ + double filter_res = input->filter_res; + std::string filename = input->filename; + std::cout << "output_callback" << std::endl; + std::cout << "filter_res: " << filter_res << std::endl; + std::cout << "filename: " << filename << std::endl; + + pcl::PointCloud::Ptr map_ptr(new pcl::PointCloud(map)); + pcl::PointCloud::Ptr map_filtered(new pcl::PointCloud()); + map_ptr->header.frame_id = "map"; + map_filtered->header.frame_id = "map"; + sensor_msgs::PointCloud2::Ptr map_msg_ptr(new sensor_msgs::PointCloud2); + + // Apply voxelgrid filter + if (filter_res == 0.0) + { + std::cout << "Original: " << map_ptr->points.size() << " points." << std::endl; + pcl::toROSMsg(*map_ptr, *map_msg_ptr); + } + else + { + pcl::VoxelGrid voxel_grid_filter; + voxel_grid_filter.setLeafSize(filter_res, filter_res, filter_res); + voxel_grid_filter.setInputCloud(map_ptr); + voxel_grid_filter.filter(*map_filtered); + std::cout << "Original: " << map_ptr->points.size() << " points." << std::endl; + std::cout << "Filtered: " << map_filtered->points.size() << " points." << std::endl; + pcl::toROSMsg(*map_filtered, *map_msg_ptr); + } + + ndt_map_pub.publish(*map_msg_ptr); + + // Writing Point Cloud data to PCD file + if (filter_res == 0.0) + { + pcl::io::savePCDFileASCII(filename, *map_ptr); + std::cout << "Saved " << map_ptr->points.size() << " data points to " << filename << "." << std::endl; + } + else + { + pcl::io::savePCDFileASCII(filename, *map_filtered); + std::cout << "Saved " << map_filtered->points.size() << " data points to " << filename << "." << std::endl; + } +} + +static void imu_odom_calc(ros::Time current_time) +{ + static ros::Time previous_time = current_time; + double diff_time = (current_time - previous_time).toSec(); + + double diff_imu_roll = imu.angular_velocity.x * diff_time; + double diff_imu_pitch = imu.angular_velocity.y * diff_time; + double diff_imu_yaw = imu.angular_velocity.z * diff_time; + + current_pose_imu_odom.roll += diff_imu_roll; + current_pose_imu_odom.pitch += diff_imu_pitch; + current_pose_imu_odom.yaw += diff_imu_yaw; + + double diff_distance = odom.twist.twist.linear.x * diff_time; + offset_imu_odom_x += diff_distance * cos(-current_pose_imu_odom.pitch) * cos(current_pose_imu_odom.yaw); + offset_imu_odom_y += diff_distance * cos(-current_pose_imu_odom.pitch) * sin(current_pose_imu_odom.yaw); + offset_imu_odom_z += diff_distance * sin(-current_pose_imu_odom.pitch); + + offset_imu_odom_roll += diff_imu_roll; + offset_imu_odom_pitch += diff_imu_pitch; + offset_imu_odom_yaw += diff_imu_yaw; + + guess_pose_imu_odom.x = previous_pose.x + offset_imu_odom_x; + guess_pose_imu_odom.y = previous_pose.y + offset_imu_odom_y; + guess_pose_imu_odom.z = previous_pose.z + offset_imu_odom_z; + guess_pose_imu_odom.roll = previous_pose.roll + offset_imu_odom_roll; + guess_pose_imu_odom.pitch = previous_pose.pitch + offset_imu_odom_pitch; + guess_pose_imu_odom.yaw = previous_pose.yaw + offset_imu_odom_yaw; + + previous_time = current_time; +} + +static void odom_calc(ros::Time current_time) +{ + static ros::Time previous_time = current_time; + double diff_time = (current_time - previous_time).toSec(); + + double diff_odom_roll = odom.twist.twist.angular.x * diff_time; + double diff_odom_pitch = odom.twist.twist.angular.y * diff_time; + double diff_odom_yaw = odom.twist.twist.angular.z * diff_time; + + current_pose_odom.roll += diff_odom_roll; + current_pose_odom.pitch += diff_odom_pitch; + current_pose_odom.yaw += diff_odom_yaw; + + double diff_distance = odom.twist.twist.linear.x * diff_time; + offset_odom_x += diff_distance * cos(-current_pose_odom.pitch) * cos(current_pose_odom.yaw); + offset_odom_y += diff_distance * cos(-current_pose_odom.pitch) * sin(current_pose_odom.yaw); + offset_odom_z += diff_distance * sin(-current_pose_odom.pitch); + + offset_odom_roll += diff_odom_roll; + offset_odom_pitch += diff_odom_pitch; + offset_odom_yaw += diff_odom_yaw; + + guess_pose_odom.x = previous_pose.x + offset_odom_x; + guess_pose_odom.y = previous_pose.y + offset_odom_y; + guess_pose_odom.z = previous_pose.z + offset_odom_z; + guess_pose_odom.roll = previous_pose.roll + offset_odom_roll; + guess_pose_odom.pitch = previous_pose.pitch + offset_odom_pitch; + guess_pose_odom.yaw = previous_pose.yaw + offset_odom_yaw; + + previous_time = current_time; +} + +static void imu_calc(ros::Time current_time) +{ + static ros::Time previous_time = current_time; + double diff_time = (current_time - previous_time).toSec(); + + double diff_imu_roll = imu.angular_velocity.x * diff_time; + double diff_imu_pitch = imu.angular_velocity.y * diff_time; + double diff_imu_yaw = imu.angular_velocity.z * diff_time; + + current_pose_imu.roll += diff_imu_roll; + current_pose_imu.pitch += diff_imu_pitch; + current_pose_imu.yaw += diff_imu_yaw; + + double accX1 = imu.linear_acceleration.x; + double accY1 = std::cos(current_pose_imu.roll) * imu.linear_acceleration.y - + std::sin(current_pose_imu.roll) * imu.linear_acceleration.z; + double accZ1 = std::sin(current_pose_imu.roll) * imu.linear_acceleration.y + + std::cos(current_pose_imu.roll) * imu.linear_acceleration.z; + + double accX2 = std::sin(current_pose_imu.pitch) * accZ1 + std::cos(current_pose_imu.pitch) * accX1; + double accY2 = accY1; + double accZ2 = std::cos(current_pose_imu.pitch) * accZ1 - std::sin(current_pose_imu.pitch) * accX1; + + double accX = std::cos(current_pose_imu.yaw) * accX2 - std::sin(current_pose_imu.yaw) * accY2; + double accY = std::sin(current_pose_imu.yaw) * accX2 + std::cos(current_pose_imu.yaw) * accY2; + double accZ = accZ2; + + offset_imu_x += current_velocity_imu_x * diff_time + accX * diff_time * diff_time / 2.0; + offset_imu_y += current_velocity_imu_y * diff_time + accY * diff_time * diff_time / 2.0; + offset_imu_z += current_velocity_imu_z * diff_time + accZ * diff_time * diff_time / 2.0; + + current_velocity_imu_x += accX * diff_time; + current_velocity_imu_y += accY * diff_time; + current_velocity_imu_z += accZ * diff_time; + + offset_imu_roll += diff_imu_roll; + offset_imu_pitch += diff_imu_pitch; + offset_imu_yaw += diff_imu_yaw; + + guess_pose_imu.x = previous_pose.x + offset_imu_x; + guess_pose_imu.y = previous_pose.y + offset_imu_y; + guess_pose_imu.z = previous_pose.z + offset_imu_z; + guess_pose_imu.roll = previous_pose.roll + offset_imu_roll; + guess_pose_imu.pitch = previous_pose.pitch + offset_imu_pitch; + guess_pose_imu.yaw = previous_pose.yaw + offset_imu_yaw; + + previous_time = current_time; +} + +static double wrapToPm(double a_num, const double a_max) +{ + if (a_num >= a_max) + { + a_num -= 2.0 * a_max; + } + return a_num; +} + +static double wrapToPmPi(double a_angle_rad) +{ + return wrapToPm(a_angle_rad, M_PI); +} + +static double calcDiffForRadian(const double lhs_rad, const double rhs_rad) +{ + double diff_rad = lhs_rad - rhs_rad; + if (diff_rad >= M_PI) + diff_rad = diff_rad - 2 * M_PI; + else if (diff_rad < -M_PI) + diff_rad = diff_rad + 2 * M_PI; + return diff_rad; +} +static void odom_callback(const nav_msgs::Odometry::ConstPtr& input) +{ + // std::cout << __func__ << std::endl; + + odom = *input; + odom_calc(input->header.stamp); +} + +static void imuUpsideDown(const sensor_msgs::Imu::Ptr input) +{ + double input_roll, input_pitch, input_yaw; + + tf::Quaternion input_orientation; + tf::quaternionMsgToTF(input->orientation, input_orientation); + tf::Matrix3x3(input_orientation).getRPY(input_roll, input_pitch, input_yaw); + + input->angular_velocity.x *= -1; + input->angular_velocity.y *= -1; + input->angular_velocity.z *= -1; + + input->linear_acceleration.x *= -1; + input->linear_acceleration.y *= -1; + input->linear_acceleration.z *= -1; + + input_roll *= -1; + input_pitch *= -1; + input_yaw *= -1; + + input->orientation = tf::createQuaternionMsgFromRollPitchYaw(input_roll, input_pitch, input_yaw); +} + +static void imu_callback(const sensor_msgs::Imu::Ptr& input) +{ + // std::cout << __func__ << std::endl; + + if (_imu_upside_down) + imuUpsideDown(input); + + const ros::Time current_time = input->header.stamp; + static ros::Time previous_time = current_time; + const double diff_time = (current_time - previous_time).toSec(); + + double imu_roll, imu_pitch, imu_yaw; + tf::Quaternion imu_orientation; + tf::quaternionMsgToTF(input->orientation, imu_orientation); + tf::Matrix3x3(imu_orientation).getRPY(imu_roll, imu_pitch, imu_yaw); + + imu_roll = wrapToPmPi(imu_roll); + imu_pitch = wrapToPmPi(imu_pitch); + imu_yaw = wrapToPmPi(imu_yaw); + + static double previous_imu_roll = imu_roll, previous_imu_pitch = imu_pitch, previous_imu_yaw = imu_yaw; + const double diff_imu_roll = calcDiffForRadian(imu_roll, previous_imu_roll); + const double diff_imu_pitch = calcDiffForRadian(imu_pitch, previous_imu_pitch); + const double diff_imu_yaw = calcDiffForRadian(imu_yaw, previous_imu_yaw); + + imu.header = input->header; + imu.linear_acceleration.x = input->linear_acceleration.x; + // imu.linear_acceleration.y = input->linear_acceleration.y; + // imu.linear_acceleration.z = input->linear_acceleration.z; + imu.linear_acceleration.y = 0; + imu.linear_acceleration.z = 0; + + if (diff_time != 0) + { + imu.angular_velocity.x = diff_imu_roll / diff_time; + imu.angular_velocity.y = diff_imu_pitch / diff_time; + imu.angular_velocity.z = diff_imu_yaw / diff_time; + } + else + { + imu.angular_velocity.x = 0; + imu.angular_velocity.y = 0; + imu.angular_velocity.z = 0; + } + + imu_calc(input->header.stamp); + + previous_time = current_time; + previous_imu_roll = imu_roll; + previous_imu_pitch = imu_pitch; + previous_imu_yaw = imu_yaw; +} + +static void points_callback(const sensor_msgs::PointCloud2::ConstPtr& input) +{ + double r; + pcl::PointXYZI p; + pcl::PointCloud tmp, scan; + pcl::PointCloud::Ptr filtered_scan_ptr(new pcl::PointCloud()); + pcl::PointCloud::Ptr transformed_scan_ptr(new pcl::PointCloud()); + tf::Quaternion q; + + Eigen::Matrix4f t_localizer(Eigen::Matrix4f::Identity()); + Eigen::Matrix4f t_base_link(Eigen::Matrix4f::Identity()); + static tf::TransformBroadcaster br; + tf::Transform transform; + + current_scan_time = input->header.stamp; + + pcl::fromROSMsg(*input, tmp); + + for (pcl::PointCloud::const_iterator item = tmp.begin(); item != tmp.end(); item++) + { + p.x = (double)item->x; + p.y = (double)item->y; + p.z = (double)item->z; + p.intensity = (double)item->intensity; + + r = sqrt(pow(p.x, 2.0) + pow(p.y, 2.0)); + if (min_scan_range < r && r < max_scan_range) + { + scan.push_back(p); + } + } + + pcl::PointCloud::Ptr scan_ptr(new pcl::PointCloud(scan)); + + // Add initial point cloud to velodyne_map + if (initial_scan_loaded == 0) + { + pcl::transformPointCloud(*scan_ptr, *transformed_scan_ptr, tf_btol); + map += *transformed_scan_ptr; + initial_scan_loaded = 1; + } + + // Apply voxelgrid filter + pcl::VoxelGrid voxel_grid_filter; + voxel_grid_filter.setLeafSize(voxel_leaf_size, voxel_leaf_size, voxel_leaf_size); + voxel_grid_filter.setInputCloud(scan_ptr); + voxel_grid_filter.filter(*filtered_scan_ptr); + + pcl::PointCloud::Ptr map_ptr(new pcl::PointCloud(map)); + + if (_method_type == MethodType::PCL_GENERIC) + { + ndt.setTransformationEpsilon(trans_eps); + ndt.setStepSize(step_size); + ndt.setResolution(ndt_res); + ndt.setMaximumIterations(max_iter); + ndt.setInputSource(filtered_scan_ptr); + } + else if (_method_type == MethodType::PCL_ANH) + { + anh_ndt.setTransformationEpsilon(trans_eps); + anh_ndt.setStepSize(step_size); + anh_ndt.setResolution(ndt_res); + anh_ndt.setMaximumIterations(max_iter); + anh_ndt.setInputSource(filtered_scan_ptr); + } +#ifdef CUDA_FOUND + else if (_method_type == MethodType::PCL_ANH_GPU) + { + anh_gpu_ndt.setTransformationEpsilon(trans_eps); + anh_gpu_ndt.setStepSize(step_size); + anh_gpu_ndt.setResolution(ndt_res); + anh_gpu_ndt.setMaximumIterations(max_iter); + anh_gpu_ndt.setInputSource(filtered_scan_ptr); + } +#endif +#ifdef USE_PCL_OPENMP + else if (_method_type == MethodType::PCL_OPENMP) + { + omp_ndt.setTransformationEpsilon(trans_eps); + omp_ndt.setStepSize(step_size); + omp_ndt.setResolution(ndt_res); + omp_ndt.setMaximumIterations(max_iter); + omp_ndt.setInputSource(filtered_scan_ptr); + } +#endif + + static bool is_first_map = true; + if (is_first_map == true) + { + if (_method_type == MethodType::PCL_GENERIC) + ndt.setInputTarget(map_ptr); + else if (_method_type == MethodType::PCL_ANH) + anh_ndt.setInputTarget(map_ptr); +#ifdef CUDA_FOUND + else if (_method_type == MethodType::PCL_ANH_GPU) + anh_gpu_ndt.setInputTarget(map_ptr); +#endif +#ifdef USE_PCL_OPENMP + else if (_method_type == MethodType::PCL_OPENMP) + omp_ndt.setInputTarget(map_ptr); +#endif + is_first_map = false; + } + + guess_pose.x = previous_pose.x + diff_x; + guess_pose.y = previous_pose.y + diff_y; + guess_pose.z = previous_pose.z + diff_z; + guess_pose.roll = previous_pose.roll; + guess_pose.pitch = previous_pose.pitch; + guess_pose.yaw = previous_pose.yaw + diff_yaw; + + if (_use_imu == true && _use_odom == true) + imu_odom_calc(current_scan_time); + if (_use_imu == true && _use_odom == false) + imu_calc(current_scan_time); + if (_use_imu == false && _use_odom == true) + odom_calc(current_scan_time); + + pose guess_pose_for_ndt; + if (_use_imu == true && _use_odom == true) + guess_pose_for_ndt = guess_pose_imu_odom; + else if (_use_imu == true && _use_odom == false) + guess_pose_for_ndt = guess_pose_imu; + else if (_use_imu == false && _use_odom == true) + guess_pose_for_ndt = guess_pose_odom; + else + guess_pose_for_ndt = guess_pose; + + Eigen::AngleAxisf init_rotation_x(guess_pose_for_ndt.roll, Eigen::Vector3f::UnitX()); + Eigen::AngleAxisf init_rotation_y(guess_pose_for_ndt.pitch, Eigen::Vector3f::UnitY()); + Eigen::AngleAxisf init_rotation_z(guess_pose_for_ndt.yaw, Eigen::Vector3f::UnitZ()); + + Eigen::Translation3f init_translation(guess_pose_for_ndt.x, guess_pose_for_ndt.y, guess_pose_for_ndt.z); + + Eigen::Matrix4f init_guess = + (init_translation * init_rotation_z * init_rotation_y * init_rotation_x).matrix() * tf_btol; + + t3_end = ros::Time::now(); + d3 = t3_end - t3_start; + + t4_start = ros::Time::now(); + + pcl::PointCloud::Ptr output_cloud(new pcl::PointCloud); + + if (_method_type == MethodType::PCL_GENERIC) + { + ndt.align(*output_cloud, init_guess); + fitness_score = ndt.getFitnessScore(); + t_localizer = ndt.getFinalTransformation(); + has_converged = ndt.hasConverged(); + final_num_iteration = ndt.getFinalNumIteration(); + transformation_probability = ndt.getTransformationProbability(); + } + else if (_method_type == MethodType::PCL_ANH) + { + anh_ndt.align(init_guess); + fitness_score = anh_ndt.getFitnessScore(); + t_localizer = anh_ndt.getFinalTransformation(); + has_converged = anh_ndt.hasConverged(); + final_num_iteration = anh_ndt.getFinalNumIteration(); + } +#ifdef CUDA_FOUND + else if (_method_type == MethodType::PCL_ANH_GPU) + { + anh_gpu_ndt.align(init_guess); + fitness_score = anh_gpu_ndt.getFitnessScore(); + t_localizer = anh_gpu_ndt.getFinalTransformation(); + has_converged = anh_gpu_ndt.hasConverged(); + final_num_iteration = anh_gpu_ndt.getFinalNumIteration(); + } +#endif +#ifdef USE_PCL_OPENMP + else if (_method_type == MethodType::PCL_OPENMP) + { + omp_ndt.align(*output_cloud, init_guess); + fitness_score = omp_ndt.getFitnessScore(); + t_localizer = omp_ndt.getFinalTransformation(); + has_converged = omp_ndt.hasConverged(); + final_num_iteration = omp_ndt.getFinalNumIteration(); + } +#endif + + t_base_link = t_localizer * tf_ltob; + + pcl::transformPointCloud(*scan_ptr, *transformed_scan_ptr, t_localizer); + + tf::Matrix3x3 mat_l, mat_b; + + mat_l.setValue(static_cast(t_localizer(0, 0)), static_cast(t_localizer(0, 1)), + static_cast(t_localizer(0, 2)), static_cast(t_localizer(1, 0)), + static_cast(t_localizer(1, 1)), static_cast(t_localizer(1, 2)), + static_cast(t_localizer(2, 0)), static_cast(t_localizer(2, 1)), + static_cast(t_localizer(2, 2))); + + mat_b.setValue(static_cast(t_base_link(0, 0)), static_cast(t_base_link(0, 1)), + static_cast(t_base_link(0, 2)), static_cast(t_base_link(1, 0)), + static_cast(t_base_link(1, 1)), static_cast(t_base_link(1, 2)), + static_cast(t_base_link(2, 0)), static_cast(t_base_link(2, 1)), + static_cast(t_base_link(2, 2))); + + // Update localizer_pose. + localizer_pose.x = t_localizer(0, 3); + localizer_pose.y = t_localizer(1, 3); + localizer_pose.z = t_localizer(2, 3); + mat_l.getRPY(localizer_pose.roll, localizer_pose.pitch, localizer_pose.yaw, 1); + + // Update ndt_pose. + ndt_pose.x = t_base_link(0, 3); + ndt_pose.y = t_base_link(1, 3); + ndt_pose.z = t_base_link(2, 3); + mat_b.getRPY(ndt_pose.roll, ndt_pose.pitch, ndt_pose.yaw, 1); + + current_pose.x = ndt_pose.x; + current_pose.y = ndt_pose.y; + current_pose.z = ndt_pose.z; + current_pose.roll = ndt_pose.roll; + current_pose.pitch = ndt_pose.pitch; + current_pose.yaw = ndt_pose.yaw; + + transform.setOrigin(tf::Vector3(current_pose.x, current_pose.y, current_pose.z)); + q.setRPY(current_pose.roll, current_pose.pitch, current_pose.yaw); + transform.setRotation(q); + + br.sendTransform(tf::StampedTransform(transform, current_scan_time, "map", "base_link")); + + scan_duration = current_scan_time - previous_scan_time; + double secs = scan_duration.toSec(); + + // Calculate the offset (curren_pos - previous_pos) + diff_x = current_pose.x - previous_pose.x; + diff_y = current_pose.y - previous_pose.y; + diff_z = current_pose.z - previous_pose.z; + diff_yaw = calcDiffForRadian(current_pose.yaw, previous_pose.yaw); + diff = sqrt(diff_x * diff_x + diff_y * diff_y + diff_z * diff_z); + + current_velocity_x = diff_x / secs; + current_velocity_y = diff_y / secs; + current_velocity_z = diff_z / secs; + + current_pose_imu.x = current_pose.x; + current_pose_imu.y = current_pose.y; + current_pose_imu.z = current_pose.z; + current_pose_imu.roll = current_pose.roll; + current_pose_imu.pitch = current_pose.pitch; + current_pose_imu.yaw = current_pose.yaw; + + current_pose_odom.x = current_pose.x; + current_pose_odom.y = current_pose.y; + current_pose_odom.z = current_pose.z; + current_pose_odom.roll = current_pose.roll; + current_pose_odom.pitch = current_pose.pitch; + current_pose_odom.yaw = current_pose.yaw; + + current_pose_imu_odom.x = current_pose.x; + current_pose_imu_odom.y = current_pose.y; + current_pose_imu_odom.z = current_pose.z; + current_pose_imu_odom.roll = current_pose.roll; + current_pose_imu_odom.pitch = current_pose.pitch; + current_pose_imu_odom.yaw = current_pose.yaw; + + current_velocity_imu_x = current_velocity_x; + current_velocity_imu_y = current_velocity_y; + current_velocity_imu_z = current_velocity_z; + + // Update position and posture. current_pos -> previous_pos + previous_pose.x = current_pose.x; + previous_pose.y = current_pose.y; + previous_pose.z = current_pose.z; + previous_pose.roll = current_pose.roll; + previous_pose.pitch = current_pose.pitch; + previous_pose.yaw = current_pose.yaw; + + previous_scan_time.sec = current_scan_time.sec; + previous_scan_time.nsec = current_scan_time.nsec; + + offset_imu_x = 0.0; + offset_imu_y = 0.0; + offset_imu_z = 0.0; + offset_imu_roll = 0.0; + offset_imu_pitch = 0.0; + offset_imu_yaw = 0.0; + + offset_odom_x = 0.0; + offset_odom_y = 0.0; + offset_odom_z = 0.0; + offset_odom_roll = 0.0; + offset_odom_pitch = 0.0; + offset_odom_yaw = 0.0; + + offset_imu_odom_x = 0.0; + offset_imu_odom_y = 0.0; + offset_imu_odom_z = 0.0; + offset_imu_odom_roll = 0.0; + offset_imu_odom_pitch = 0.0; + offset_imu_odom_yaw = 0.0; + + // Calculate the shift between added_pos and current_pos + double shift = sqrt(pow(current_pose.x - added_pose.x, 2.0) + pow(current_pose.y - added_pose.y, 2.0)); + if (shift >= min_add_scan_shift) + { + map += *transformed_scan_ptr; + added_pose.x = current_pose.x; + added_pose.y = current_pose.y; + added_pose.z = current_pose.z; + added_pose.roll = current_pose.roll; + added_pose.pitch = current_pose.pitch; + added_pose.yaw = current_pose.yaw; + + if (_method_type == MethodType::PCL_GENERIC) + ndt.setInputTarget(map_ptr); + else if (_method_type == MethodType::PCL_ANH) + { + if (_incremental_voxel_update == true) + anh_ndt.updateVoxelGrid(transformed_scan_ptr); + else + anh_ndt.setInputTarget(map_ptr); + } +#ifdef CUDA_FOUND + else if (_method_type == MethodType::PCL_ANH_GPU) + anh_gpu_ndt.setInputTarget(map_ptr); +#endif +#ifdef USE_PCL_OPENMP + else if (_method_type == MethodType::PCL_OPENMP) + omp_ndt.setInputTarget(map_ptr); +#endif + } + + sensor_msgs::PointCloud2::Ptr map_msg_ptr(new sensor_msgs::PointCloud2); + pcl::toROSMsg(*map_ptr, *map_msg_ptr); + ndt_map_pub.publish(*map_msg_ptr); + + q.setRPY(current_pose.roll, current_pose.pitch, current_pose.yaw); + current_pose_msg.header.frame_id = "map"; + current_pose_msg.header.stamp = current_scan_time; + current_pose_msg.pose.position.x = current_pose.x; + current_pose_msg.pose.position.y = current_pose.y; + current_pose_msg.pose.position.z = current_pose.z; + current_pose_msg.pose.orientation.x = q.x(); + current_pose_msg.pose.orientation.y = q.y(); + current_pose_msg.pose.orientation.z = q.z(); + current_pose_msg.pose.orientation.w = q.w(); + + current_pose_pub.publish(current_pose_msg); + + // Write log + if (!ofs) + { + std::cerr << "Could not open " << filename << "." << std::endl; + exit(1); + } + + ofs << input->header.seq << "," + << input->header.stamp << "," + << input->header.frame_id << "," + << scan_ptr->size() << "," + << filtered_scan_ptr->size() << "," + << std::fixed << std::setprecision(5) << current_pose.x << "," + << std::fixed << std::setprecision(5) << current_pose.y << "," + << std::fixed << std::setprecision(5) << current_pose.z << "," + << current_pose.roll << "," + << current_pose.pitch << "," + << current_pose.yaw << "," + << final_num_iteration << "," + << fitness_score << "," + << ndt_res << "," + << step_size << "," + << trans_eps << "," + << max_iter << "," + << voxel_leaf_size << "," + << min_scan_range << "," + << max_scan_range << "," + << min_add_scan_shift << std::endl; + + std::cout << "-----------------------------------------------------------------" << std::endl; + std::cout << "Sequence number: " << input->header.seq << std::endl; + std::cout << "Number of scan points: " << scan_ptr->size() << " points." << std::endl; + std::cout << "Number of filtered scan points: " << filtered_scan_ptr->size() << " points." << std::endl; + std::cout << "transformed_scan_ptr: " << transformed_scan_ptr->points.size() << " points." << std::endl; + std::cout << "map: " << map.points.size() << " points." << std::endl; + std::cout << "NDT has converged: " << has_converged << std::endl; + std::cout << "Fitness score: " << fitness_score << std::endl; + std::cout << "Number of iteration: " << final_num_iteration << std::endl; + std::cout << "(x,y,z,roll,pitch,yaw):" << std::endl; + std::cout << "(" << current_pose.x << ", " << current_pose.y << ", " << current_pose.z << ", " << current_pose.roll + << ", " << current_pose.pitch << ", " << current_pose.yaw << ")" << std::endl; + std::cout << "Transformation Matrix:" << std::endl; + std::cout << t_localizer << std::endl; + std::cout << "shift: " << shift << std::endl; + std::cout << "-----------------------------------------------------------------" << std::endl; +} + +int main(int argc, char** argv) +{ + previous_pose.x = 0.0; + previous_pose.y = 0.0; + previous_pose.z = 0.0; + previous_pose.roll = 0.0; + previous_pose.pitch = 0.0; + previous_pose.yaw = 0.0; + + ndt_pose.x = 0.0; + ndt_pose.y = 0.0; + ndt_pose.z = 0.0; + ndt_pose.roll = 0.0; + ndt_pose.pitch = 0.0; + ndt_pose.yaw = 0.0; + + current_pose.x = 0.0; + current_pose.y = 0.0; + current_pose.z = 0.0; + current_pose.roll = 0.0; + current_pose.pitch = 0.0; + current_pose.yaw = 0.0; + + current_pose_imu.x = 0.0; + current_pose_imu.y = 0.0; + current_pose_imu.z = 0.0; + current_pose_imu.roll = 0.0; + current_pose_imu.pitch = 0.0; + current_pose_imu.yaw = 0.0; + + guess_pose.x = 0.0; + guess_pose.y = 0.0; + guess_pose.z = 0.0; + guess_pose.roll = 0.0; + guess_pose.pitch = 0.0; + guess_pose.yaw = 0.0; + + added_pose.x = 0.0; + added_pose.y = 0.0; + added_pose.z = 0.0; + added_pose.roll = 0.0; + added_pose.pitch = 0.0; + added_pose.yaw = 0.0; + + diff_x = 0.0; + diff_y = 0.0; + diff_z = 0.0; + diff_yaw = 0.0; + + offset_imu_x = 0.0; + offset_imu_y = 0.0; + offset_imu_z = 0.0; + offset_imu_roll = 0.0; + offset_imu_pitch = 0.0; + offset_imu_yaw = 0.0; + + offset_odom_x = 0.0; + offset_odom_y = 0.0; + offset_odom_z = 0.0; + offset_odom_roll = 0.0; + offset_odom_pitch = 0.0; + offset_odom_yaw = 0.0; + + offset_imu_odom_x = 0.0; + offset_imu_odom_y = 0.0; + offset_imu_odom_z = 0.0; + offset_imu_odom_roll = 0.0; + offset_imu_odom_pitch = 0.0; + offset_imu_odom_yaw = 0.0; + + ros::init(argc, argv, "ndt_mapping"); + + ros::NodeHandle nh; + ros::NodeHandle private_nh("~"); + + // Set log file name. + char buffer[80]; + std::time_t now = std::time(NULL); + std::tm* pnow = std::localtime(&now); + std::strftime(buffer, 80, "%Y%m%d_%H%M%S", pnow); + filename = "ndt_mapping_" + std::string(buffer) + ".csv"; + ofs.open(filename.c_str(), std::ios::app); + + // write header for log file + if (!ofs) + { + std::cerr << "Could not open " << filename << "." << std::endl; + exit(1); + } + + ofs << "input->header.seq" << "," + << "input->header.stamp" << "," + << "input->header.frame_id" << "," + << "scan_ptr->size()" << "," + << "filtered_scan_ptr->size()" << "," + << "current_pose.x" << "," + << "current_pose.y" << "," + << "current_pose.z" << "," + << "current_pose.roll" << "," + << "current_pose.pitch" << "," + << "current_pose.yaw" << "," + << "final_num_iteration" << "," + << "fitness_score" << "," + << "ndt_res" << "," + << "step_size" << "," + << "trans_eps" << "," + << "max_iter" << "," + << "voxel_leaf_size" << "," + << "min_scan_range" << "," + << "max_scan_range" << "," + << "min_add_scan_shift" << std::endl; + + // setting parameters + int method_type_tmp = 0; + private_nh.getParam("method_type", method_type_tmp); + _method_type = static_cast(method_type_tmp); + private_nh.getParam("use_odom", _use_odom); + private_nh.getParam("use_imu", _use_imu); + private_nh.getParam("imu_upside_down", _imu_upside_down); + private_nh.getParam("imu_topic", _imu_topic); + private_nh.getParam("incremental_voxel_update", _incremental_voxel_update); + + std::cout << "method_type: " << static_cast(_method_type) << std::endl; + std::cout << "use_odom: " << _use_odom << std::endl; + std::cout << "use_imu: " << _use_imu << std::endl; + std::cout << "imu_upside_down: " << _imu_upside_down << std::endl; + std::cout << "imu_topic: " << _imu_topic << std::endl; + std::cout << "incremental_voxel_update: " << _incremental_voxel_update << std::endl; + + if (nh.getParam("tf_x", _tf_x) == false) + { + std::cout << "tf_x is not set." << std::endl; + return 1; + } + if (nh.getParam("tf_y", _tf_y) == false) + { + std::cout << "tf_y is not set." << std::endl; + return 1; + } + if (nh.getParam("tf_z", _tf_z) == false) + { + std::cout << "tf_z is not set." << std::endl; + return 1; + } + if (nh.getParam("tf_roll", _tf_roll) == false) + { + std::cout << "tf_roll is not set." << std::endl; + return 1; + } + if (nh.getParam("tf_pitch", _tf_pitch) == false) + { + std::cout << "tf_pitch is not set." << std::endl; + return 1; + } + if (nh.getParam("tf_yaw", _tf_yaw) == false) + { + std::cout << "tf_yaw is not set." << std::endl; + return 1; + } + + std::cout << "(tf_x,tf_y,tf_z,tf_roll,tf_pitch,tf_yaw): (" << _tf_x << ", " << _tf_y << ", " << _tf_z << ", " + << _tf_roll << ", " << _tf_pitch << ", " << _tf_yaw << ")" << std::endl; + +#ifndef CUDA_FOUND + if (_method_type == MethodType::PCL_ANH_GPU) + { + std::cerr << "**************************************************************" << std::endl; + std::cerr << "[ERROR]PCL_ANH_GPU is not built. Please use other method type." << std::endl; + std::cerr << "**************************************************************" << std::endl; + exit(1); + } +#endif +#ifndef USE_PCL_OPENMP + if (_method_type == MethodType::PCL_OPENMP) + { + std::cerr << "**************************************************************" << std::endl; + std::cerr << "[ERROR]PCL_OPENMP is not built. Please use other method type." << std::endl; + std::cerr << "**************************************************************" << std::endl; + exit(1); + } +#endif + + Eigen::Translation3f tl_btol(_tf_x, _tf_y, _tf_z); // tl: translation + Eigen::AngleAxisf rot_x_btol(_tf_roll, Eigen::Vector3f::UnitX()); // rot: rotation + Eigen::AngleAxisf rot_y_btol(_tf_pitch, Eigen::Vector3f::UnitY()); + Eigen::AngleAxisf rot_z_btol(_tf_yaw, Eigen::Vector3f::UnitZ()); + tf_btol = (tl_btol * rot_z_btol * rot_y_btol * rot_x_btol).matrix(); + tf_ltob = tf_btol.inverse(); + + map.header.frame_id = "map"; + + ndt_map_pub = nh.advertise("/ndt_map", 1000); + current_pose_pub = nh.advertise("/current_pose", 1000); + + ros::Subscriber param_sub = nh.subscribe("config/ndt_mapping", 10, param_callback); + ros::Subscriber output_sub = nh.subscribe("config/ndt_mapping_output", 10, output_callback); + ros::Subscriber points_sub = nh.subscribe("points_raw", 100000, points_callback); + ros::Subscriber odom_sub = nh.subscribe("/vehicle/odom", 100000, odom_callback); + ros::Subscriber imu_sub = nh.subscribe(_imu_topic, 100000, imu_callback); + + ros::spin(); + + return 0; +}