From 931ac7577e51ec93cc372f8a8ee0bf95cbaac63b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Juraj=20Or=C5=A1uli=C4=87?= Date: Tue, 20 Nov 2018 17:07:31 +0100 Subject: [PATCH] windows build fixes - use nanosecond precision for time points explicitly - build loam as static lib - explicit cast of double RPY to float Angle - use only needed components of pcl --- CMakeLists.txt | 2 +- include/loam_velodyne/common.h | 3 +-- include/loam_velodyne/time_utils.h | 3 ++- src/lib/CMakeLists.txt | 2 +- src/lib/LaserMapping.cpp | 2 +- 5 files changed, 6 insertions(+), 6 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 8297219b..f9b5ef47 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -12,7 +12,7 @@ find_package(catkin REQUIRED COMPONENTS pcl_conversions) find_package(Eigen3 REQUIRED) -find_package(PCL REQUIRED) +find_package(PCL REQUIRED COMPONENTS common filters) include_directories( include diff --git a/include/loam_velodyne/common.h b/include/loam_velodyne/common.h index 1b93d77f..74367513 100644 --- a/include/loam_velodyne/common.h +++ b/include/loam_velodyne/common.h @@ -65,9 +65,8 @@ inline void publishCloudMsg(ros::Publisher& publisher, // ROS time adapters inline Time fromROSTime(ros::Time const& rosTime) { - auto epoch = std::chrono::system_clock::time_point(); auto since_epoch = std::chrono::seconds(rosTime.sec) + std::chrono::nanoseconds(rosTime.nsec); - return epoch + since_epoch; + return Time() + since_epoch; } inline ros::Time toROSTime(Time const& time_point) diff --git a/include/loam_velodyne/time_utils.h b/include/loam_velodyne/time_utils.h index 100043b1..b0667ba8 100644 --- a/include/loam_velodyne/time_utils.h +++ b/include/loam_velodyne/time_utils.h @@ -5,7 +5,8 @@ namespace loam { /** \brief A standard non-ROS alternative to ros::Time.*/ - using Time = std::chrono::system_clock::time_point; + using Time = + std::chrono::time_point; // helper function inline double toSec(Time::duration duration) diff --git a/src/lib/CMakeLists.txt b/src/lib/CMakeLists.txt index 4371f779..4726e021 100644 --- a/src/lib/CMakeLists.txt +++ b/src/lib/CMakeLists.txt @@ -1,4 +1,4 @@ -add_library(loam +add_library(loam STATIC math_utils.h ScanRegistration.cpp BasicScanRegistration.cpp diff --git a/src/lib/LaserMapping.cpp b/src/lib/LaserMapping.cpp index 4d2ef003..3fcba681 100644 --- a/src/lib/LaserMapping.cpp +++ b/src/lib/LaserMapping.cpp @@ -223,7 +223,7 @@ void LaserMapping::imuHandler(const sensor_msgs::Imu::ConstPtr& imuIn) tf::Quaternion orientation; tf::quaternionMsgToTF(imuIn->orientation, orientation); tf::Matrix3x3(orientation).getRPY(roll, pitch, yaw); - updateIMU({ fromROSTime(imuIn->header.stamp) , roll, pitch }); + updateIMU({ fromROSTime(imuIn->header.stamp) , static_cast(roll), static_cast(pitch) }); } void LaserMapping::spin()