Merge pull request #602 from bulwahn/fix-build-with-gcc8

some adjustments to build with gcc-8
This commit is contained in:
Lukas Bulwahn 2018-06-18 05:31:25 +02:00 committed by GitHub
commit d165e589f4
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
8 changed files with 126 additions and 2 deletions

View File

@ -0,0 +1,46 @@
From a0b3ce9ca5c69a945695c1c83dab7937a3d99b83 Mon Sep 17 00:00:00 2001
From: Jochen Sprickerhof <git@jochen.sprickerhof.de>
Date: Sat, 5 May 2018 23:58:13 +0200
Subject: [PATCH] Dereference shared_ptr, fix for GCC8
Upstream-Status: Accepted [https://github.com/PointCloudLibrary/pcl/commit/a0b3ce9ca5c69a945695c1c83dab7937a3d99b83]
This patch has been generated with:
`git format-patch -1 a0b3ce9ca5c69a945695c1c83dab7937a3d99b83`
in the pcl repository.
Signed-off-by: Lukas Bulwahn <lukas.bulwahn@gmail.com>
---
segmentation/include/pcl/segmentation/ground_plane_comparator.h | 2 +-
segmentation/include/pcl/segmentation/plane_coefficient_comparator.h | 2 +-
2 files changed, 2 insertions(+), 2 deletions(-)
diff --git a/segmentation/include/pcl/segmentation/ground_plane_comparator.h b/segmentation/include/pcl/segmentation/ground_plane_comparator.h
index e39354d..f96f38b 100644
--- a/segmentation/include/pcl/segmentation/ground_plane_comparator.h
+++ b/segmentation/include/pcl/segmentation/ground_plane_comparator.h
@@ -147,7 +147,7 @@ namespace pcl
const std::vector<float>&
getPlaneCoeffD () const
{
- return (plane_coeff_d_);
+ return (*plane_coeff_d_);
}
/** \brief Set the tolerance in radians for difference in normal direction between neighboring points, to be considered part of the same plane.
diff --git a/segmentation/include/pcl/segmentation/plane_coefficient_comparator.h b/segmentation/include/pcl/segmentation/plane_coefficient_comparator.h
index 9c94813..a21725a 100644
--- a/segmentation/include/pcl/segmentation/plane_coefficient_comparator.h
+++ b/segmentation/include/pcl/segmentation/plane_coefficient_comparator.h
@@ -141,7 +141,7 @@ namespace pcl
const std::vector<float>&
getPlaneCoeffD () const
{
- return (plane_coeff_d_);
+ return (*plane_coeff_d_);
}
/** \brief Set the tolerance in radians for difference in normal direction between neighboring points, to be considered part of the same plane.
--
2.7.4

View File

@ -45,8 +45,9 @@ based on already pre-existing patterns in the CMakeLists.txt file.
Signed-off-by: Lukas Bulwahn <lukas.bulwahn@oss.bmw-carit.de> Signed-off-by: Lukas Bulwahn <lukas.bulwahn@oss.bmw-carit.de>
Upstream-Status: Pending [https://github.com/PointCloudLibrary/pcl/pull/1730] Upstream-Status: Inappropriate [openembedded specific]
Signed-off-by: Lukas Bulwahn <lukas.bulwahn@gmail.com>
--- ---
CMakeLists.txt | 2 +- CMakeLists.txt | 2 +-
cmake/Modules/FindOpenNI.cmake | 2 +- cmake/Modules/FindOpenNI.cmake | 2 +-

View File

@ -10,6 +10,7 @@ SRC_URI[md5sum] = "8c1308be2c13106e237e4a4204a32cca"
SRC_URI[sha256sum] = "9e54b0c1b59a67a386b9b0f4acb2d764272ff9a0377b825c4ed5eedf46ebfcf4" SRC_URI[sha256sum] = "9e54b0c1b59a67a386b9b0f4acb2d764272ff9a0377b825c4ed5eedf46ebfcf4"
SRC_URI += "file://0001-make-the-pcl-library-compile-with-gcc6.patch" SRC_URI += "file://0001-make-the-pcl-library-compile-with-gcc6.patch"
SRC_URI += "file://0001-Dereference-shared_ptr-fix-for-GCC8.patch"
S = "${WORKDIR}/pcl-${P}" S = "${WORKDIR}/pcl-${P}"
@ -39,3 +40,8 @@ CXXFLAGS += "${@bb.utils.contains("TARGET_CC_ARCH", "-mfpmath=sse", "", "-ffloat
inherit cmake inherit cmake
FILES_${PN}-dev += "${datadir}/${PN}-1.8/*.cmake" FILES_${PN}-dev += "${datadir}/${PN}-1.8/*.cmake"
# The build is really memory hungry (at least with gcc8), even with just -j 8 it triggers OOMK on system with 32GB ram
# High memory needs mentioned in: https://github.com/PointCloudLibrary/pcl/issues/2284
# Setting just empty doesn't work, ninja will by default use number of cores available
PARALLEL_MAKE = "-j1"

View File

@ -0,0 +1,32 @@
From 89a976959e6a84b363ea2c5e53685b2e2b810711 Mon Sep 17 00:00:00 2001
From: Maarten de Vries <maarten@de-vri.es>
Date: Fri, 11 May 2018 07:55:17 +0200
Subject: [PATCH] Fix allocator type to pass GCC8 static assert. (#888)
Upstream-Status: Backport [from kinetic, https://github.com/ros-planning/moveit/commit/89a976959e6a84b363ea2c5e53685b2e2b810711]
This patch has been generated with:
`git format-patch -1 89a976959e6a84b363ea2c5e53685b2e2b810711`
in the moveit repository.
Signed-off-by: Lukas Bulwahn <lukas.bulwahn@gmail.com>
---
moveit_core/robot_model/include/moveit/robot_model/link_model.h | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/moveit_core/robot_model/include/moveit/robot_model/link_model.h b/moveit_core/robot_model/include/moveit/robot_model/link_model.h
index d8aec2f..3f2b1b6 100644
--- a/moveit_core/robot_model/include/moveit/robot_model/link_model.h
+++ b/moveit_core/robot_model/include/moveit/robot_model/link_model.h
@@ -65,7 +65,7 @@ typedef std::map<std::string, const LinkModel*> LinkModelMapConst;
/** \brief Map from link model instances to Eigen transforms */
typedef std::map<const LinkModel*, Eigen::Affine3d, std::less<const LinkModel*>,
- Eigen::aligned_allocator<std::pair<const LinkModel*, Eigen::Affine3d> > >
+ Eigen::aligned_allocator<std::pair<const LinkModel* const, Eigen::Affine3d> > >
LinkTransformMap;
/** \brief A link from the robot. Contains the constant transform applied to the link and its geometry */
--
2.7.4

View File

@ -6,3 +6,5 @@ LIC_FILES_CHKSUM = "file://package.xml;beginline=14;endline=14;md5=d566ef916e9de
DEPENDS = "roslib boost eigen-conversions fcl octomap eigen-stl-containers geometric-shapes kdl-parser moveit-msgs srdfdom cmake-modules" DEPENDS = "roslib boost eigen-conversions fcl octomap eigen-stl-containers geometric-shapes kdl-parser moveit-msgs srdfdom cmake-modules"
require moveit.inc require moveit.inc
SRC_URI += "file://0001-Fix-allocator-type-to-pass-GCC8-static-assert.-888.patch;patchdir=.."

View File

@ -3,7 +3,7 @@ SECTION = "devel"
LICENSE = "BSD" LICENSE = "BSD"
LIC_FILES_CHKSUM = "file://package.xml;beginline=13;endline=13;md5=d566ef916e9dedc494f5f793a6690ba5" LIC_FILES_CHKSUM = "file://package.xml;beginline=13;endline=13;md5=d566ef916e9dedc494f5f793a6690ba5"
DEPENDS = "moveit-core moveit-ros-perception dynamic-reconfigure ${PYTHON_PN}-rospkg libtinyxml" DEPENDS = "moveit-core moveit-ros-perception dynamic-reconfigure ${PYTHON_PN}-rospkg libtinyxml tf-conversions"
require moveit.inc require moveit.inc

View File

@ -0,0 +1,35 @@
From 65e4ce3de9747e359f38db65cf78763f75bcfbd1 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?J=C3=B8rgen=20Nordmoen?= <nordmoen@users.noreply.github.com>
Date: Fri, 4 May 2018 15:50:39 +0200
Subject: [PATCH] Changed invocation to `add` to conform template syntax
(#1388)
This change fixes issue #1383
Upstream-Status: Backport [from melodic, https://github.com/ros/ros_comm/commit/65e4ce3de9747e359f38db65cf78763f75bcfbd1]
This patch has been generated with:
`git format-patch -1 65e4ce3de9747e359f38db65cf78763f75bcfbd1`
in the ros_comm repository.
Signed-off-by: Lukas Bulwahn <lukas.bulwahn@gmail.com>
---
utilities/message_filters/include/message_filters/synchronizer.h | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/utilities/message_filters/include/message_filters/synchronizer.h b/utilities/message_filters/include/message_filters/synchronizer.h
index 7891890..1c14a6f 100644
--- a/utilities/message_filters/include/message_filters/synchronizer.h
+++ b/utilities/message_filters/include/message_filters/synchronizer.h
@@ -355,7 +355,7 @@ private:
template<int i>
void cb(const typename mpl::at_c<Events, i>::type& evt)
{
- this->add<i>(evt);
+ this->template add<i>(evt);
}
uint32_t queue_size_;
--
2.7.4

View File

@ -8,3 +8,5 @@ DEPENDS = "boost rosconsole roscpp xmlrpcpp"
require ros-comm.inc require ros-comm.inc
ROS_PKG_SUBDIR = "utilities" ROS_PKG_SUBDIR = "utilities"
SRC_URI += "file://0001-Changed-invocation-to-add-to-conform-template-syntax.patch;patchdir=../.."