├── CMakeLists.txt ├── README.md ├── doc └── calibration_result.jpg ├── include └── multi_lidar_calibrator.h ├── launch └── multi_lidar_calibrator.launch ├── package.xml └── src ├── multi_lidar_calibrator.cpp └── multi_lidar_calibrator_node.cpp /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.12) 2 | project(multi_lidar_calibrator) 3 | 4 | 5 | find_package(catkin REQUIRED COMPONENTS 6 | roscpp 7 | std_msgs 8 | sensor_msgs 9 | geometry_msgs 10 | pcl_ros 11 | pcl_conversions 12 | ) 13 | 14 | catkin_package(CATKIN_DEPENDS 15 | std_msgs 16 | sensor_msgs 17 | geometry_msgs 18 | ) 19 | 20 | find_package(OpenCV REQUIRED) 21 | 22 | ########### 23 | ## Build ## 24 | ########### 25 | 26 | include_directories( 27 | ${catkin_INCLUDE_DIRS} 28 | include 29 | ) 30 | 31 | SET(CMAKE_CXX_FLAGS "-O2 -g -Wall ${CMAKE_CXX_FLAGS}") 32 | SET(CMAKE_CXX_STANDARD 11) 33 | 34 | # MultiLidar Calibrator 35 | add_library(multi_lidar_calibrator_lib SHARED 36 | src/multi_lidar_calibrator.cpp 37 | include/multi_lidar_calibrator.h) 38 | 39 | target_include_directories(multi_lidar_calibrator_lib PRIVATE 40 | ${OpenCV_INCLUDE_DIRS} 41 | ) 42 | 43 | target_link_libraries(multi_lidar_calibrator_lib 44 | ${catkin_LIBRARIES} 45 | ) 46 | 47 | add_executable(multi_lidar_calibrator 48 | src/multi_lidar_calibrator_node.cpp 49 | ) 50 | 51 | target_include_directories(multi_lidar_calibrator PRIVATE 52 | include) 53 | 54 | target_link_libraries(multi_lidar_calibrator 55 | multi_lidar_calibrator_lib) 56 | 57 | install(TARGETS 58 | multi_lidar_calibrator multi_lidar_calibrator_lib 59 | ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 60 | LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 61 | RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) 62 | 63 | install(DIRECTORY launch/ 64 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch 65 | PATTERN ".svn" EXCLUDE) -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # Multi LiDAR Calibrator 2 | 3 | This package allows to obtain the extrinsic calibration between two PointClouds with the help of the NDT algorithm. 4 | 5 | The `multi_lidar_calibrator` node receives two `PointCloud2` messages (parent and child), and an initialization pose. 6 | If possible, the transformation required to transform the child to the parent point cloud is calculated, and output to the terminal. 7 | 8 | ## How to launch 9 | 10 | 1. **You'll need to provide an initial guess, otherwise the transformation won't converge.** 11 | 12 | 2. In a sourced terminal: 13 | 14 | Using rosrun 15 | 16 | `rosrun multi_lidar_calibrator multi_lidar_calibrator _points_child_src:=/lidar_child/points_raw _points_parent_src:=/lidar_parent/points_raw _x:=0.0 _y:=0.0 _z:=0.0 _roll:=0.0 _pitch:=0.0 _yaw:=0.0` 17 | 18 | Using roslaunch 19 | 20 | `roslaunch multi_lidar_calibrator multi_lidar_calibrator.launch points_child_src:=/lidar_child/points_raw points_parent_src:=/lidar_parent/points_raw x:=0.0 y:=0.0 z:=0.0 roll:=0.0 pitch:=0.0 yaw:=0.0` 21 | 22 | 3. Play a rosbag with both lidar data `/lidar_child/points_raw` and `/lidar_parent/points_raw` 23 | 24 | 4. The resulting transformation will be shown in the terminal as shown in the *Output* section. 25 | 26 | 5. Open RViz and set the fixed frame to the Parent 27 | 28 | 6. Add both point cloud `/lidar_parent/points_raw` and `/points_calibrated` 29 | 30 | 7. If the algorithm converged, both PointClouds will be shown in rviz. 31 | 32 | ## Input topics 33 | 34 | |Parameter| Type| Description| 35 | ----------|-----|-------- 36 | |`points_parent_src`|*String* |PointCloud topic name to subscribe and synchronize with the child.| 37 | |`points_child_src`|*String*|PointCloud topic name to subscribe and synchronize with the parent.| 38 | |`voxel_size`|*double*|Size of the Voxel used to downsample the CHILD pointcloud. Default: 0.5| 39 | |`ndt_epsilon`|*double*|The transformation epsilon in order for an optimization to be considered as having converged to the final solution. Default: 0.01| 40 | |`ndt_step_size`|*double*|Set/change the newton line search maximum step length. Default: 0.1| 41 | |`ndt_resolution`|*double*|Size of the Voxel used to downsample the PARENT pointcloud. Default: 1.0| 42 | |`ndt_iterations`|*double*|The maximum number of iterations the internal optimization should run for. Default: 400| 43 | |`x`|*double*|Initial Guess of the transformation x. Meters| 44 | |`y`|*double*|Initial Guess of the transformation y. Meters| 45 | |`z`|*double*|Initial Guess of the transformation z. Meters| 46 | |`roll`|*double*|Initial Guess of the transformation roll. Radians| 47 | |`pitch`|*double*|Initial Guess of the transformation pitch. Radians| 48 | |`yaw`|*double*|Initial Guess of the transformation yaw. Radians| 49 | 50 | ## Output 51 | 52 | 1. Child Point cloud transformed to the Parent frame and published in `/points_calibrated`. 53 | 1. Output in the terminal showing the X,Y,Z,Yaw,Pitch,Roll transformation between child and parent. These values can be used later with the `static_transform_publisher`. 54 | 55 | 56 | ### Output example: 57 | 58 | ``` 59 | transformation from ChildFrame to ParentFrame 60 | This transformation can be replicated using: 61 | 62 | rosrun tf static_transform_publisher 1.7096 -0.101048 -0.56108 1.5708 0.00830573 0.843 /ParentFrame /ChildFrame 10 63 | ``` 64 | The figure below shows two lidar sensors calibrated by this node. 65 | One is shown in gray while the other is show in blue. 66 | Image obtained from rviz. 67 | 68 | ![Calibration Result](doc/calibration_result.jpg) -------------------------------------------------------------------------------- /doc/calibration_result.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/wutaoo/multi_lidar_calibration/f048afcc6afaedb78fc84124c2988aa0ccdd7209/doc/calibration_result.jpg -------------------------------------------------------------------------------- /include/multi_lidar_calibrator.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2018-2019 Autoware Foundation. All rights reserved. 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | ******************** 16 | * v1.0: amc-nu (abrahammonrroy@yahoo.com) 17 | * 18 | * multi_lidar_calibrator.h 19 | * 20 | * Created on: Feb 27, 2018 21 | */ 22 | 23 | #ifndef PROJECT_MULTI_LIDAR_CALIBRATOR_H 24 | #define PROJECT_MULTI_LIDAR_CALIBRATOR_H 25 | 26 | 27 | #include 28 | #include 29 | #include 30 | #include 31 | #include 32 | #include 33 | #include 34 | #include 35 | #include 36 | #include 37 | #include 38 | #include 39 | #include 40 | #include 41 | #include 42 | #include 43 | #include 44 | #include 45 | 46 | 47 | #include 48 | 49 | #define __APP_NAME__ "multi_lidar_calibrator" 50 | 51 | class ROSMultiLidarCalibratorApp 52 | 53 | { 54 | ros::NodeHandle node_handle_; 55 | ros::Publisher calibrated_cloud_publisher_; 56 | 57 | ros::Subscriber initialpose_subscriber_; 58 | 59 | double voxel_size_; 60 | double ndt_epsilon_; 61 | double ndt_step_size_; 62 | double ndt_resolution_; 63 | 64 | double initial_x_; 65 | double initial_y_; 66 | double initial_z_; 67 | double initial_roll_; 68 | double initial_pitch_; 69 | double initial_yaw_; 70 | 71 | int ndt_iterations_; 72 | 73 | //tf::Quaternion initialpose_quaternion_; 74 | //tf::Vector3 initialpose_position_; 75 | 76 | std::string parent_frame_; 77 | std::string child_frame_; 78 | 79 | Eigen::Matrix4f current_guess_; 80 | 81 | typedef 82 | message_filters::sync_policies::ApproximateTime SyncPolicyT; 84 | 85 | typedef pcl::PointXYZI PointT; 86 | 87 | message_filters::Subscriber *cloud_parent_subscriber_, *cloud_child_subscriber_; 88 | message_filters::Synchronizer *cloud_synchronizer_; 89 | 90 | /*! 91 | * Receives 2 synchronized point cloud messages. 92 | * @param[in] in_parent_cloud_msg Message containing pointcloud classified as ground. 93 | * @param[in] in_child_cloud_msg Message containing pointcloud classified as obstacle. 94 | */ 95 | void PointsCallback(const sensor_msgs::PointCloud2::ConstPtr& in_parent_cloud_msg, 96 | const sensor_msgs::PointCloud2::ConstPtr& in_child_cloud_msg); 97 | 98 | //void InitialPoseCallback(geometry_msgs::PoseWithCovarianceStamped::ConstPtr in_initialpose); 99 | 100 | /*! 101 | * Obtains parameters from the command line, initializes subscribers and publishers. 102 | * @param in_private_handle ROS private handle to get parameters for this node. 103 | */ 104 | void InitializeROSIo(ros::NodeHandle& in_private_handle); 105 | 106 | /*! 107 | * Applies a Voxel Grid filter to the point cloud 108 | * @param in_cloud_ptr point cloud to downsample 109 | * @param out_cloud_ptr downsampled point cloud 110 | * @param in_leaf_size voxel side size 111 | */ 112 | void DownsampleCloud(pcl::PointCloud::ConstPtr in_cloud_ptr, pcl::PointCloud::Ptr out_cloud_ptr, double in_leaf_size); 113 | 114 | /*! 115 | * Publishes a PointCloud in the specified publisher 116 | * @param in_publisher Publisher to use 117 | * @param in_cloud_to_publish_ptr Cloud to Publish 118 | */ 119 | void PublishCloud(const ros::Publisher& in_publisher, pcl::PointCloud::ConstPtr in_cloud_to_publish_ptr); 120 | 121 | public: 122 | void Run(); 123 | 124 | ROSMultiLidarCalibratorApp(); 125 | }; 126 | 127 | #endif //PROJECT_MULTI_LIDAR_CALIBRATOR_H 128 | -------------------------------------------------------------------------------- /launch/multi_lidar_calibrator.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | -------------------------------------------------------------------------------- /package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | multi_lidar_calibrator 4 | 1.11.0 5 | The multi_lidar_calibrator package allows to obtain the extrinsic calibration between two lidar sensors 6 | 7 | amc-nu 8 | 9 | Apache 2 10 | 11 | catkin 12 | autoware_build_flags 13 | 14 | roscpp 15 | std_msgs 16 | geometry_msgs 17 | sensor_msgs 18 | pcl_conversions 19 | pcl_ros 20 | qtbase5-dev 21 | 22 | message_runtime 23 | roscpp 24 | std_msgs 25 | geometry_msgs 26 | sensor_msgs 27 | pcl_conversions 28 | pcl_ros 29 | libqt5-core 30 | 31 | rosunit 32 | 33 | 34 | 35 | -------------------------------------------------------------------------------- /src/multi_lidar_calibrator.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2018-2019 Autoware Foundation. All rights reserved. 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | ******************** 16 | * v1.0: amc-nu (abrahammonrroy@yahoo.com) 17 | * 18 | * multi_lidar_calibrator.cpp 19 | * 20 | * Created on: Feb 27, 2018 21 | */ 22 | 23 | #include "multi_lidar_calibrator.h" 24 | 25 | 26 | void ROSMultiLidarCalibratorApp::PublishCloud(const ros::Publisher& in_publisher, pcl::PointCloud::ConstPtr in_cloud_to_publish_ptr) 27 | { 28 | sensor_msgs::PointCloud2 cloud_msg; 29 | pcl::toROSMsg(*in_cloud_to_publish_ptr, cloud_msg); 30 | cloud_msg.header.frame_id = parent_frame_; 31 | in_publisher.publish(cloud_msg); 32 | } 33 | 34 | void ROSMultiLidarCalibratorApp::PointsCallback(const sensor_msgs::PointCloud2::ConstPtr &in_parent_cloud_msg, 35 | const sensor_msgs::PointCloud2::ConstPtr &in_child_cloud_msg) 36 | { 37 | pcl::PointCloud::Ptr in_parent_cloud(new pcl::PointCloud); 38 | pcl::PointCloud::Ptr in_child_cloud(new pcl::PointCloud); 39 | 40 | pcl::PointCloud::Ptr child_filtered_cloud (new pcl::PointCloud); 41 | 42 | pcl::fromROSMsg(*in_parent_cloud_msg, *in_parent_cloud); 43 | pcl::fromROSMsg(*in_child_cloud_msg, *in_child_cloud); 44 | 45 | parent_frame_ = in_parent_cloud_msg->header.frame_id; 46 | child_frame_ = in_child_cloud_msg->header.frame_id; 47 | 48 | DownsampleCloud(in_child_cloud, child_filtered_cloud, voxel_size_); 49 | 50 | // Initializing Normal Distributions Transform (NDT). 51 | pcl::NormalDistributionsTransform ndt; 52 | 53 | ndt.setTransformationEpsilon(ndt_epsilon_); 54 | ndt.setStepSize(ndt_step_size_); 55 | ndt.setResolution(ndt_resolution_); 56 | 57 | ndt.setMaximumIterations(ndt_iterations_); 58 | 59 | ndt.setInputSource(child_filtered_cloud); 60 | ndt.setInputTarget(in_parent_cloud); 61 | 62 | pcl::PointCloud::Ptr output_cloud(new pcl::PointCloud); 63 | 64 | Eigen::Translation3f init_translation(initial_x_, initial_y_, initial_z_); 65 | Eigen::AngleAxisf init_rotation_x(initial_roll_, Eigen::Vector3f::UnitX()); 66 | Eigen::AngleAxisf init_rotation_y(initial_pitch_, Eigen::Vector3f::UnitY()); 67 | Eigen::AngleAxisf init_rotation_z(initial_yaw_, Eigen::Vector3f::UnitZ()); 68 | 69 | Eigen::Matrix4f init_guess_ = (init_translation * init_rotation_z * init_rotation_y * init_rotation_x).matrix(); 70 | 71 | if(current_guess_ == Eigen::Matrix4f::Identity()) 72 | { 73 | current_guess_ = init_guess_; 74 | } 75 | 76 | ndt.align(*output_cloud, current_guess_); 77 | 78 | std::cout << "Normal Distributions Transform converged:" << ndt.hasConverged () 79 | << " score: " << ndt.getFitnessScore () << " prob:" << ndt.getTransformationProbability() << std::endl; 80 | 81 | std::cout << "transformation from " << child_frame_ << " to " << parent_frame_ << std::endl; 82 | 83 | // Transforming unfiltered, input cloud using found transform. 84 | pcl::transformPointCloud (*in_child_cloud, *output_cloud, ndt.getFinalTransformation()); 85 | 86 | current_guess_ = ndt.getFinalTransformation(); 87 | 88 | Eigen::Matrix3f rotation_matrix = current_guess_.block(0,0,3,3); 89 | Eigen::Vector3f translation_vector = current_guess_.block(0,3,3,1); 90 | std::cout << "This transformation can be replicated using:" << std::endl; 91 | std::cout << "rosrun tf static_transform_publisher " << translation_vector.transpose() 92 | << " " << rotation_matrix.eulerAngles(2,1,0).transpose() << " /" << parent_frame_ 93 | << " /" << child_frame_ << " 10" << std::endl; 94 | 95 | std::cout << "Corresponding transformation matrix:" << std::endl 96 | << std::endl << current_guess_ << std::endl << std::endl; 97 | 98 | PublishCloud(calibrated_cloud_publisher_, output_cloud); 99 | // timer end 100 | //auto end = std::chrono::system_clock::now(); 101 | //auto usec = std::chrono::duration_cast(end - start).count(); 102 | //std::cout << "time: " << usec / 1000.0 << " [msec]" << std::endl; 103 | 104 | } 105 | 106 | /*void ROSMultiLidarCalibratorApp::InitialPoseCallback(geometry_msgs::PoseWithCovarianceStamped::ConstPtr in_initialpose) 107 | { 108 | ROS_INFO("[%s] Initial Pose received.", __APP_NAME__); 109 | tf::Quaternion pose_quaternion(in_initialpose->pose.pose.orientation.x, 110 | in_initialpose->pose.pose.orientation.y, 111 | in_initialpose->pose.pose.orientation.z, 112 | in_initialpose->pose.pose.orientation.w); 113 | 114 | //rotation 115 | initialpose_quaternion_ = pose_quaternion; 116 | 117 | //translation 118 | initialpose_position_.setX(in_initialpose->pose.pose.position.x); 119 | initialpose_position_.setY(in_initialpose->pose.pose.position.y); 120 | initialpose_position_.setZ(in_initialpose->pose.pose.position.z); 121 | 122 | 123 | }*/ 124 | 125 | void ROSMultiLidarCalibratorApp::DownsampleCloud(pcl::PointCloud::ConstPtr in_cloud_ptr, 126 | pcl::PointCloud::Ptr out_cloud_ptr, 127 | double in_leaf_size) 128 | { 129 | pcl::VoxelGrid voxelized; 130 | voxelized.setInputCloud(in_cloud_ptr); 131 | voxelized.setLeafSize((float)in_leaf_size, (float)in_leaf_size, (float)in_leaf_size); 132 | voxelized.filter(*out_cloud_ptr); 133 | } 134 | 135 | void ROSMultiLidarCalibratorApp::InitializeROSIo(ros::NodeHandle &in_private_handle) 136 | { 137 | //get params 138 | std::string points_parent_topic_str, points_child_topic_str; 139 | std::string initial_pose_topic_str = "/initialpose"; 140 | std::string calibrated_points_topic_str = "/points_calibrated"; 141 | 142 | in_private_handle.param("points_parent_src", points_parent_topic_str, "points_raw"); 143 | ROS_INFO("[%s] points_parent_src: %s",__APP_NAME__, points_parent_topic_str.c_str()); 144 | 145 | in_private_handle.param("points_child_src", points_child_topic_str, "points_raw"); 146 | ROS_INFO("[%s] points_child_src: %s",__APP_NAME__, points_child_topic_str.c_str()); 147 | 148 | in_private_handle.param("voxel_size", voxel_size_, 0.1); 149 | ROS_INFO("[%s] ndt_epsilon: %.2f",__APP_NAME__, voxel_size_); 150 | 151 | in_private_handle.param("ndt_epsilon", ndt_epsilon_, 0.01); 152 | ROS_INFO("[%s] voxel_size: %.2f",__APP_NAME__, ndt_epsilon_); 153 | 154 | in_private_handle.param("ndt_step_size", ndt_step_size_, 0.1); 155 | ROS_INFO("[%s] ndt_step_size: %.2f",__APP_NAME__, ndt_step_size_); 156 | 157 | in_private_handle.param("ndt_resolution", ndt_resolution_, 1.0); 158 | ROS_INFO("[%s] ndt_resolution: %.2f",__APP_NAME__, ndt_resolution_); 159 | 160 | in_private_handle.param("ndt_iterations", ndt_iterations_, 400); 161 | ROS_INFO("[%s] ndt_iterations: %d",__APP_NAME__, ndt_iterations_); 162 | 163 | in_private_handle.param("x", initial_x_, 0.0); 164 | in_private_handle.param("y", initial_y_, 0.0); 165 | in_private_handle.param("z", initial_z_, 0.0); 166 | in_private_handle.param("roll", initial_roll_, 0.0); 167 | in_private_handle.param("pitch", initial_pitch_, 0.0); 168 | in_private_handle.param("yaw", initial_yaw_, 0.0); 169 | 170 | ROS_INFO("[%s] Initialization Transform x: %.2f y: %.2f z: %.2f roll: %.2f pitch: %.2f yaw: %.2f", __APP_NAME__, 171 | initial_x_, initial_y_, initial_z_, 172 | initial_roll_, initial_pitch_, initial_yaw_); 173 | 174 | //generate subscribers and synchronizer 175 | cloud_parent_subscriber_ = new message_filters::Subscriber(node_handle_, 176 | points_parent_topic_str, 10); 177 | ROS_INFO("[%s] Subscribing to... %s",__APP_NAME__, points_parent_topic_str.c_str()); 178 | 179 | cloud_child_subscriber_ = new message_filters::Subscriber(node_handle_, 180 | points_child_topic_str, 10); 181 | ROS_INFO("[%s] Subscribing to... %s",__APP_NAME__, points_child_topic_str.c_str()); 182 | 183 | /*initialpose_subscriber_ = node_handle_.subscribe(initial_pose_topic_str, 10, 184 | &ROSMultiLidarCalibratorApp::InitialPoseCallback, this); 185 | ROS_INFO("[%s] Subscribing to... %s",__APP_NAME__, initial_pose_topic_str.c_str());*/ 186 | 187 | calibrated_cloud_publisher_ = node_handle_.advertise(calibrated_points_topic_str, 1); 188 | ROS_INFO("[%s] Publishing PointCloud to... %s",__APP_NAME__, calibrated_points_topic_str.c_str()); 189 | 190 | cloud_synchronizer_ = 191 | new message_filters::Synchronizer(SyncPolicyT(100), 192 | *cloud_parent_subscriber_, 193 | *cloud_child_subscriber_); 194 | cloud_synchronizer_->registerCallback(boost::bind(&ROSMultiLidarCalibratorApp::PointsCallback, this, _1, _2)); 195 | 196 | } 197 | 198 | 199 | void ROSMultiLidarCalibratorApp::Run() 200 | { 201 | ros::NodeHandle private_node_handle("~"); 202 | 203 | InitializeROSIo(private_node_handle); 204 | 205 | ROS_INFO("[%s] Ready. Waiting for data...",__APP_NAME__); 206 | 207 | ros::spin(); 208 | 209 | ROS_INFO("[%s] END",__APP_NAME__); 210 | } 211 | 212 | ROSMultiLidarCalibratorApp::ROSMultiLidarCalibratorApp() 213 | { 214 | //initialpose_quaternion_ = tf::Quaternion::getIdentity(); 215 | current_guess_ = Eigen::Matrix4f::Identity(); 216 | } -------------------------------------------------------------------------------- /src/multi_lidar_calibrator_node.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright 2018-2019 Autoware Foundation. All rights reserved. 3 | * 4 | * Licensed under the Apache License, Version 2.0 (the "License"); 5 | * you may not use this file except in compliance with the License. 6 | * You may obtain a copy of the License at 7 | * 8 | * http://www.apache.org/licenses/LICENSE-2.0 9 | * 10 | * Unless required by applicable law or agreed to in writing, software 11 | * distributed under the License is distributed on an "AS IS" BASIS, 12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | * See the License for the specific language governing permissions and 14 | * limitations under the License. 15 | ******************** 16 | * v1.0: amc-nu (abrahammonrroy@yahoo.com) 17 | * 18 | * multi_lidar_calibrator_node.cpp 19 | * 20 | * Created on: Feb 27 2018 21 | */ 22 | 23 | #include "multi_lidar_calibrator.h" 24 | 25 | int main(int argc, char **argv) 26 | { 27 | ros::init(argc, argv, __APP_NAME__); 28 | 29 | ROSMultiLidarCalibratorApp app; 30 | 31 | app.Run(); 32 | 33 | return 0; 34 | } 35 | --------------------------------------------------------------------------------