Skip to content
This repository was archived by the owner on Nov 13, 2017. It is now read-only.

Commit 9283d9a

Browse files
author
Alain Sanguinetti
committed
Revert "#592 fixed by manually resetting the kinematics loader"
This reverts commit ef55f65.
1 parent 1250659 commit 9283d9a

File tree

6 files changed

+8
-32
lines changed

6 files changed

+8
-32
lines changed

planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -62,8 +62,6 @@ class KinematicsPluginLoader
6262
{
6363
}
6464

65-
~KinematicsPluginLoader();
66-
6765
/** \brief Use a default kinematics solver (\e solver_plugin) for
6866
all the groups in the robot model. The default timeout for the
6967
solver is \e solve_timeout and the default number of IK attempts

planning/kinematics_plugin_loader/src/kinematics_plugin_loader.cpp

Lines changed: 0 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -76,11 +76,6 @@ class KinematicsPluginLoader::KinematicsLoaderImpl
7676
}
7777
}
7878

79-
~KinematicsLoaderImpl( ) {
80-
kinematics_loader_.reset(); // we delete it manually
81-
ROS_DEBUG( "KinematicsLoaderImpl destructor");
82-
}
83-
8479
/**
8580
* \brief Helper function to decide which, and how many, tip frames a planning group has
8681
* \param jmg - joint model group pointer
@@ -248,11 +243,6 @@ void kinematics_plugin_loader::KinematicsPluginLoader::status() const
248243
ROS_INFO("Loader function was never required");
249244
}
250245

251-
kinematics_plugin_loader::KinematicsPluginLoader::~KinematicsPluginLoader()
252-
{
253-
ROS_DEBUG( "KinematicsPluginLoader destructor" );
254-
}
255-
256246
robot_model::SolverAllocatorFn kinematics_plugin_loader::KinematicsPluginLoader::getLoaderFunction()
257247
{
258248
moveit::tools::Profiler::ScopedStart prof_start;

planning/planning_scene_monitor/src/current_state_monitor.cpp

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -51,8 +51,6 @@ planning_scene_monitor::CurrentStateMonitor::CurrentStateMonitor(const robot_mod
5151
planning_scene_monitor::CurrentStateMonitor::~CurrentStateMonitor()
5252
{
5353
stopStateMonitor();
54-
55-
ROS_DEBUG( "CurrentStateMonitor destructor finished." );
5654
}
5755

5856
robot_state::RobotStatePtr planning_scene_monitor::CurrentStateMonitor::getCurrentState() const

planning/robot_model_loader/src/robot_model_loader.cpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -51,12 +51,11 @@ robot_model_loader::RobotModelLoader::RobotModelLoader(const Options &opt)
5151
configure(opt);
5252
}
5353

54-
robot_model_loader::RobotModelLoader::~RobotModelLoader() {
54+
robot_model_loader::RobotModelLoader::~RobotModelLoader()
55+
{
5556
model_.reset();
5657
rdf_loader_.reset();
5758
kinematics_loader_.reset();
58-
59-
ROS_DEBUG( "Robot model loader destructor" );
6059
}
6160

6261
namespace

planning_interface/common_planning_interface_objects/src/common_objects.cpp

Lines changed: 0 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -48,17 +48,9 @@ struct SharedStorage
4848

4949
~SharedStorage()
5050
{
51-
ROS_DEBUG( "Shared storage destructor begins" );
5251
tf_.reset();
53-
ROS_DEBUG( "TF was reset" );
54-
5552
state_monitors_.clear();
56-
ROS_DEBUG( "state_monitors_ was cleared" );
57-
5853
model_loaders_.clear();
59-
ROS_DEBUG( "model_loaders_ was cleared" );
60-
61-
ROS_DEBUG( "Shared storage destructor finished" );
6254
}
6355

6456
boost::mutex lock_;

planning_interface/move_group_interface/src/move_group.cpp

Lines changed: 6 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -195,11 +195,10 @@ class MoveGroup::MoveGroupImpl
195195
}
196196
}
197197

198-
~MoveGroupImpl() {
199-
ROS_DEBUG( "MoveGroupImpl destructor begins" );
198+
~MoveGroupImpl()
199+
{
200200
if (constraints_init_thread_)
201201
constraints_init_thread_->join();
202-
ROS_DEBUG( "MoveGroupImpl destructor finished" );
203202
}
204203

205204
const boost::shared_ptr<tf::Transformer>& getTF() const
@@ -1091,13 +1090,13 @@ moveit::planning_interface::MoveGroup::MoveGroup(const Options &opt, const boost
10911090
impl_ = new MoveGroupImpl(opt, tf ? tf : getSharedTF(), wait_for_server);
10921091
}
10931092

1094-
moveit::planning_interface::MoveGroup::~MoveGroup() {
1093+
moveit::planning_interface::MoveGroup::~MoveGroup()
1094+
{
10951095
delete impl_;
1096-
1097-
ROS_DEBUG( "MoveGroup destructor finished" );
10981096
}
10991097

1100-
const std::string& moveit::planning_interface::MoveGroup::getName() const {
1098+
const std::string& moveit::planning_interface::MoveGroup::getName() const
1099+
{
11011100
return impl_->getOptions().group_name_;
11021101
}
11031102

0 commit comments

Comments
 (0)