diff --git a/nexus_motion_planner/src/motion_planner_server.cpp b/nexus_motion_planner/src/motion_planner_server.cpp index 08c9cf3..9355f57 100644 --- a/nexus_motion_planner/src/motion_planner_server.cpp +++ b/nexus_motion_planner/src/motion_planner_server.cpp @@ -293,11 +293,6 @@ MotionPlannerServer::~MotionPlannerServer() { _spin_thread.join(); } - - if (_cache_spin_thread.joinable()) - { - _cache_spin_thread.join(); - } } //============================================================================== diff --git a/nexus_motion_planner/src/motion_planner_server.hpp b/nexus_motion_planner/src/motion_planner_server.hpp index ee0e714..9032bf4 100644 --- a/nexus_motion_planner/src/motion_planner_server.hpp +++ b/nexus_motion_planner/src/motion_planner_server.hpp @@ -99,9 +99,6 @@ class MotionPlannerServer : public rclcpp_lifecycle::LifecycleNode rclcpp::Node::SharedPtr _internal_node; std::thread _spin_thread; - rclcpp::Node::SharedPtr _internal_cache_node; - std::thread _cache_spin_thread; - // MoveIt planning std::vector _manipulators; bool _use_move_group_interfaces;