Skip to content

Commit

Permalink
Merge pull request #168 from fawkesrobotics/thofmann/pcl-ros-melodic
Browse files Browse the repository at this point in the history
Adapt pcl_utils to ROS melodic with updated PCL
  • Loading branch information
morxa authored Sep 25, 2019
2 parents bcbbac4 + d8f3699 commit d0fc04e
Showing 1 changed file with 24 additions and 24 deletions.
48 changes: 24 additions & 24 deletions src/libs/pcl_utils/utils.h
Original file line number Diff line number Diff line change
Expand Up @@ -78,12 +78,12 @@ template <typename PointT>
inline void
set_time(pcl::PointCloud<PointT> &cloud, const fawkes::Time &time)
{
#if defined(HAVE_ROS_PCL) || defined(ROSCPP_TYPES_H)
#if PCL_VERSION_COMPARE(>=, 1, 7, 0)
cloud.header.stamp = time.in_usec();
#else
# if defined(HAVE_ROS_PCL) || defined(ROSCPP_TYPES_H)
cloud.header.stamp.sec = time.get_sec();
cloud.header.stamp.nsec = time.get_usec() * 1000;
#else
# if PCL_VERSION_COMPARE(>=, 1, 7, 0)
cloud.header.stamp = time.in_usec();
# else
PointCloudTimestamp pclts;
pclts.time.sec = time.get_sec();
Expand Down Expand Up @@ -129,11 +129,11 @@ template <typename PointT>
inline void
get_time(const fawkes::RefPtr<const pcl::PointCloud<PointT>> &cloud, fawkes::Time &time)
{
#if defined(HAVE_ROS_PCL) || defined(ROSCPP_TYPES_H)
time.set_time(cloud->header.stamp.sec, cloud->header.stamp.nsec / 1000);
#else
# if PCL_VERSION_COMPARE(>=, 1, 7, 0)
#if PCL_VERSION_COMPARE(>=, 1, 7, 0)
time.set_time(cloud->header.stamp / 1000000U, cloud->header.stamp % 1000000);
#else
# if defined(HAVE_ROS_PCL) || defined(ROSCPP_TYPES_H)
time.set_time(cloud->header.stamp.sec, cloud->header.stamp.nsec / 1000);
# else
PointCloudTimestamp pclts;
pclts.timestamp = cloud->header.stamp;
Expand All @@ -152,11 +152,11 @@ template <typename PointT>
inline void
get_time(const fawkes::RefPtr<pcl::PointCloud<PointT>> &cloud, fawkes::Time &time)
{
#if defined(HAVE_ROS_PCL) || defined(ROSCPP_TYPES_H)
time.set_time(cloud->header.stamp.sec, cloud->header.stamp.nsec / 1000);
#else
# if PCL_VERSION_COMPARE(>=, 1, 7, 0)
#if PCL_VERSION_COMPARE(>=, 1, 7, 0)
time.set_time(cloud->header.stamp / 1000000U, cloud->header.stamp % 1000000);
#else
# if defined(HAVE_ROS_PCL) || defined(ROSCPP_TYPES_H)
time.set_time(cloud->header.stamp.sec, cloud->header.stamp.nsec / 1000);
# else
PointCloudTimestamp pclts;
pclts.timestamp = cloud->header.stamp;
Expand All @@ -175,11 +175,11 @@ template <typename PointT>
inline void
get_time(const pcl::PointCloud<PointT> &cloud, fawkes::Time &time)
{
#if defined(HAVE_ROS_PCL) || defined(ROSCPP_TYPES_H)
time.set_time(cloud.header.stamp.sec, cloud.header.stamp.nsec / 1000);
#else
# if PCL_VERSION_COMPARE(>=, 1, 7, 0)
#if PCL_VERSION_COMPARE(>=, 1, 7, 0)
time.set_time(cloud.header.stamp / 1000000U, cloud.header.stamp % 1000000);
#else
# if defined(HAVE_ROS_PCL) || defined(ROSCPP_TYPES_H)
time.set_time(cloud.header.stamp.sec, cloud.header.stamp.nsec / 1000);
# else
PointCloudTimestamp pclts;
pclts.timestamp = cloud.header.stamp;
Expand All @@ -198,11 +198,11 @@ template <typename PointT>
inline void
get_time(const boost::shared_ptr<pcl::PointCloud<PointT>> &cloud, fawkes::Time &time)
{
#if defined(HAVE_ROS_PCL) || defined(ROSCPP_TYPES_H)
time.set_time(cloud->header.stamp.sec, cloud->header.stamp.nsec / 1000);
#else
# if PCL_VERSION_COMPARE(>=, 1, 7, 0)
#if PCL_VERSION_COMPARE(>=, 1, 7, 0)
time.set_time(cloud->header.stamp / 1000000U, cloud->header.stamp % 1000000);
#else
# if defined(HAVE_ROS_PCL) || defined(ROSCPP_TYPES_H)
time.set_time(cloud->header.stamp.sec, cloud->header.stamp.nsec / 1000);
# else
PointCloudTimestamp pclts;
pclts.timestamp = cloud->header.stamp;
Expand All @@ -221,11 +221,11 @@ template <typename PointT>
inline void
get_time(const boost::shared_ptr<const pcl::PointCloud<PointT>> &cloud, fawkes::Time &time)
{
#if defined(HAVE_ROS_PCL) || defined(ROSCPP_TYPES_H)
time.set_time(cloud->header.stamp.sec, cloud->header.stamp.nsec / 1000);
#else
# if PCL_VERSION_COMPARE(>=, 1, 7, 0)
#if PCL_VERSION_COMPARE(>=, 1, 7, 0)
time.set_time(cloud->header.stamp / 1000000U, cloud->header.stamp % 1000000);
#else
# if defined(HAVE_ROS_PCL) || defined(ROSCPP_TYPES_H)
time.set_time(cloud->header.stamp.sec, cloud->header.stamp.nsec / 1000);
# else
PointCloudTimestamp pclts;
pclts.timestamp = cloud->header.stamp;
Expand Down

0 comments on commit d0fc04e

Please sign in to comment.