Changes have been pushed for the repository "fawkesrobotics/fawkes".
Clone: https://github.com/fawkesrobotics/fawkes.git Gitweb: https://github.com/fawkesrobotics/fawkes The branch, thofmann/pcl-ros-melodic has been updated discards 83e6ddd73874a0c8cf708aed65a76f64b76345a3 (commit) to d8f36997a4e0a34f4003adafd46573245625d542 (commit) This update added new revisions after undoing existing revisions. That is to say, the old revision is not a strict subset of the new revision. This situation occurs when you --force push a change and generate a repository containing something like this: * -- * -- B -- O -- O -- O (83e6ddd73874a0c8cf708aed65a76f64b76345a3) \ N -- N -- N (d8f36997a4e0a34f4003adafd46573245625d542) When this happens we assume that you've already had alert emails for all of the O revisions, and so we here report only the revisions in the N branch from the common base, B. https://github.com/fawkesrobotics/fawkes/tree/thofmann/pcl-ros-melodic Those revisions listed above that are new to this repository have not appeared on any other notification email; so we list those revisions in full, below. - *Log* --------------------------------------------------------------- commit d8f36997a4e0a34f4003adafd46573245625d542 Author: Till Hofmann <hofm...@kbsg.rwth-aachen.de> AuthorDate: Wed Sep 25 19:20:48 2019 +0200 Commit: Till Hofmann <hofm...@kbsg.rwth-aachen.de> CommitDate: Wed Sep 25 19:27:51 2019 +0200 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. https://github.com/fawkesrobotics/fawkes/commit/d8f36997a - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - *Summary* ----------------------------------------------------------- src/libs/pcl_utils/utils.h | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) - *Diffs* ------------------------------------------------------------- - *commit* d8f36997a4e0a34f4003adafd46573245625d542 - - - - - - - - - - Author: Till Hofmann <hofm...@kbsg.rwth-aachen.de> Date: Wed Sep 25 19:20:48 2019 +0200 Subject: pcl_utils: adapt to ROS melodic with updated PCL src/libs/pcl_utils/utils.h | 48 +++++++++++++++++++++++----------------------- 1 file changed, 24 insertions(+), 24 deletions(-) _Diff for modified files_: diff --git a/src/libs/pcl_utils/utils.h b/src/libs/pcl_utils/utils.h index fdbcda074..ebc404cef 100644 --- a/src/libs/pcl_utils/utils.h +++ b/src/libs/pcl_utils/utils.h @@ -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(); @@ -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; @@ -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; @@ -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; @@ -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; @@ -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; _______________________________________________ fawkes-commits mailing list fawkes-commits@lists.kbsg.rwth-aachen.de https://lists.kbsg.rwth-aachen.de/listinfo/fawkes-commits