From 4386d0cc606f0d67d95a0835e9682323a1da7842 Mon Sep 17 00:00:00 2001 From: v4hn Date: Mon, 22 Feb 2021 14:36:20 +0100 Subject: [PATCH] remove roscpp as an export dependency for the core package We do use ROS in the background. But there is no need for a public export dependency on it. This patch also resolves the following catkin_lint issue: moveit_task_constructor_core: CMakeLists.txt(17): error: package 'roscpp' must be in CATKIN_DEPENDS in catkin_package() --- core/include/moveit/task_constructor/stage_p.h | 8 +++----- core/package.xml | 4 +++- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/core/include/moveit/task_constructor/stage_p.h b/core/include/moveit/task_constructor/stage_p.h index b83b368f..87842b43 100644 --- a/core/include/moveit/task_constructor/stage_p.h +++ b/core/include/moveit/task_constructor/stage_p.h @@ -43,8 +43,6 @@ #include #include -#include - #include #include @@ -116,8 +114,8 @@ public: /// enforce only one parent exists inline bool setParent(ContainerBase* parent) { if (parent_) { - ROS_ERROR_STREAM("Tried to add stage '" << name() << "' to two parents"); - return false; // it's not allowed to add a stage to a parent if it already has one + // it's not allowed to add a stage to a parent if it already has one + throw std::runtime_error("Tried to add stage '" + name() + "' to two parents"); } parent_ = parent; return true; @@ -181,7 +179,7 @@ protected: std::list states_; // storage for created states ordered solutions_; std::list failures_; - size_t num_failures_ = 0; // num of failures if not stored + std::size_t num_failures_ = 0; // num of failures if not stored private: // !! items write-accessed only by ContainerBasePrivate to maintain hierarchy !! diff --git a/core/package.xml b/core/package.xml index bb6e89b0..27deebfa 100644 --- a/core/package.xml +++ b/core/package.xml @@ -9,9 +9,11 @@ catkin + roscpp + roscpp + eigen_conversions geometry_msgs - roscpp moveit_core moveit_ros_planning moveit_ros_planning_interface