mirror of
https://github.com/moveit/moveit_task_constructor.git
synced 2025-11-04 14:49:57 +08:00
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()
This commit is contained in:
parent
685fec6070
commit
4386d0cc60
@ -43,8 +43,6 @@
|
||||
#include <moveit/task_constructor/cost_terms.h>
|
||||
#include <moveit/task_constructor/cost_queue.h>
|
||||
|
||||
#include <ros/ros.h>
|
||||
|
||||
#include <ostream>
|
||||
#include <chrono>
|
||||
|
||||
@ -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<InterfaceState> states_; // storage for created states
|
||||
ordered<SolutionBaseConstPtr> solutions_;
|
||||
std::list<SolutionBaseConstPtr> 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 !!
|
||||
|
||||
@ -9,9 +9,11 @@
|
||||
|
||||
<buildtool_depend>catkin</buildtool_depend>
|
||||
|
||||
<build_depend>roscpp</build_depend>
|
||||
<exec_depend>roscpp</exec_depend>
|
||||
|
||||
<depend>eigen_conversions</depend>
|
||||
<depend>geometry_msgs</depend>
|
||||
<depend>roscpp</depend>
|
||||
<depend>moveit_core</depend>
|
||||
<depend>moveit_ros_planning</depend>
|
||||
<depend>moveit_ros_planning_interface</depend>
|
||||
|
||||
Loading…
Reference in New Issue
Block a user