Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Windows build fixes #99

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
3 changes: 1 addition & 2 deletions include/loam_velodyne/common.h
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
3 changes: 2 additions & 1 deletion include/loam_velodyne/time_utils.h
Original file line number Diff line number Diff line change
Expand Up @@ -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<std::chrono::system_clock, std::chrono::nanoseconds>;

// helper function
inline double toSec(Time::duration duration)
Expand Down
2 changes: 1 addition & 1 deletion src/lib/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
add_library(loam
add_library(loam STATIC
math_utils.h
ScanRegistration.cpp
BasicScanRegistration.cpp
Expand Down
2 changes: 1 addition & 1 deletion src/lib/LaserMapping.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<float>(roll), static_cast<float>(pitch) });
}

void LaserMapping::spin()
Expand Down