Skip to content

Commit d8f3699

Browse files
committed
pcl_utils: adapt to ROS melodic with updated PCL
ROS melodic also ships with an updated PCL. Change the order of the version checks so we first check the PCL version, and only then check if we have an old PCL with ROS.
1 parent bcbbac4 commit d8f3699

1 file changed

Lines changed: 24 additions & 24 deletions

File tree

src/libs/pcl_utils/utils.h

Lines changed: 24 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -78,12 +78,12 @@ template <typename PointT>
7878
inline void
7979
set_time(pcl::PointCloud<PointT> &cloud, const fawkes::Time &time)
8080
{
81-
#if defined(HAVE_ROS_PCL) || defined(ROSCPP_TYPES_H)
81+
#if PCL_VERSION_COMPARE(>=, 1, 7, 0)
82+
cloud.header.stamp = time.in_usec();
83+
#else
84+
# if defined(HAVE_ROS_PCL) || defined(ROSCPP_TYPES_H)
8285
cloud.header.stamp.sec = time.get_sec();
8386
cloud.header.stamp.nsec = time.get_usec() * 1000;
84-
#else
85-
# if PCL_VERSION_COMPARE(>=, 1, 7, 0)
86-
cloud.header.stamp = time.in_usec();
8787
# else
8888
PointCloudTimestamp pclts;
8989
pclts.time.sec = time.get_sec();
@@ -129,11 +129,11 @@ template <typename PointT>
129129
inline void
130130
get_time(const fawkes::RefPtr<const pcl::PointCloud<PointT>> &cloud, fawkes::Time &time)
131131
{
132-
#if defined(HAVE_ROS_PCL) || defined(ROSCPP_TYPES_H)
133-
time.set_time(cloud->header.stamp.sec, cloud->header.stamp.nsec / 1000);
134-
#else
135-
# if PCL_VERSION_COMPARE(>=, 1, 7, 0)
132+
#if PCL_VERSION_COMPARE(>=, 1, 7, 0)
136133
time.set_time(cloud->header.stamp / 1000000U, cloud->header.stamp % 1000000);
134+
#else
135+
# if defined(HAVE_ROS_PCL) || defined(ROSCPP_TYPES_H)
136+
time.set_time(cloud->header.stamp.sec, cloud->header.stamp.nsec / 1000);
137137
# else
138138
PointCloudTimestamp pclts;
139139
pclts.timestamp = cloud->header.stamp;
@@ -152,11 +152,11 @@ template <typename PointT>
152152
inline void
153153
get_time(const fawkes::RefPtr<pcl::PointCloud<PointT>> &cloud, fawkes::Time &time)
154154
{
155-
#if defined(HAVE_ROS_PCL) || defined(ROSCPP_TYPES_H)
156-
time.set_time(cloud->header.stamp.sec, cloud->header.stamp.nsec / 1000);
157-
#else
158-
# if PCL_VERSION_COMPARE(>=, 1, 7, 0)
155+
#if PCL_VERSION_COMPARE(>=, 1, 7, 0)
159156
time.set_time(cloud->header.stamp / 1000000U, cloud->header.stamp % 1000000);
157+
#else
158+
# if defined(HAVE_ROS_PCL) || defined(ROSCPP_TYPES_H)
159+
time.set_time(cloud->header.stamp.sec, cloud->header.stamp.nsec / 1000);
160160
# else
161161
PointCloudTimestamp pclts;
162162
pclts.timestamp = cloud->header.stamp;
@@ -175,11 +175,11 @@ template <typename PointT>
175175
inline void
176176
get_time(const pcl::PointCloud<PointT> &cloud, fawkes::Time &time)
177177
{
178-
#if defined(HAVE_ROS_PCL) || defined(ROSCPP_TYPES_H)
179-
time.set_time(cloud.header.stamp.sec, cloud.header.stamp.nsec / 1000);
180-
#else
181-
# if PCL_VERSION_COMPARE(>=, 1, 7, 0)
178+
#if PCL_VERSION_COMPARE(>=, 1, 7, 0)
182179
time.set_time(cloud.header.stamp / 1000000U, cloud.header.stamp % 1000000);
180+
#else
181+
# if defined(HAVE_ROS_PCL) || defined(ROSCPP_TYPES_H)
182+
time.set_time(cloud.header.stamp.sec, cloud.header.stamp.nsec / 1000);
183183
# else
184184
PointCloudTimestamp pclts;
185185
pclts.timestamp = cloud.header.stamp;
@@ -198,11 +198,11 @@ template <typename PointT>
198198
inline void
199199
get_time(const boost::shared_ptr<pcl::PointCloud<PointT>> &cloud, fawkes::Time &time)
200200
{
201-
#if defined(HAVE_ROS_PCL) || defined(ROSCPP_TYPES_H)
202-
time.set_time(cloud->header.stamp.sec, cloud->header.stamp.nsec / 1000);
203-
#else
204-
# if PCL_VERSION_COMPARE(>=, 1, 7, 0)
201+
#if PCL_VERSION_COMPARE(>=, 1, 7, 0)
205202
time.set_time(cloud->header.stamp / 1000000U, cloud->header.stamp % 1000000);
203+
#else
204+
# if defined(HAVE_ROS_PCL) || defined(ROSCPP_TYPES_H)
205+
time.set_time(cloud->header.stamp.sec, cloud->header.stamp.nsec / 1000);
206206
# else
207207
PointCloudTimestamp pclts;
208208
pclts.timestamp = cloud->header.stamp;
@@ -221,11 +221,11 @@ template <typename PointT>
221221
inline void
222222
get_time(const boost::shared_ptr<const pcl::PointCloud<PointT>> &cloud, fawkes::Time &time)
223223
{
224-
#if defined(HAVE_ROS_PCL) || defined(ROSCPP_TYPES_H)
225-
time.set_time(cloud->header.stamp.sec, cloud->header.stamp.nsec / 1000);
226-
#else
227-
# if PCL_VERSION_COMPARE(>=, 1, 7, 0)
224+
#if PCL_VERSION_COMPARE(>=, 1, 7, 0)
228225
time.set_time(cloud->header.stamp / 1000000U, cloud->header.stamp % 1000000);
226+
#else
227+
# if defined(HAVE_ROS_PCL) || defined(ROSCPP_TYPES_H)
228+
time.set_time(cloud->header.stamp.sec, cloud->header.stamp.nsec / 1000);
229229
# else
230230
PointCloudTimestamp pclts;
231231
pclts.timestamp = cloud->header.stamp;

0 commit comments

Comments
 (0)