add explicit destructor for Task

Without this rml_ would be deleted before all IK plugins are unloaded
and class_loader still can't handle this...
This commit is contained in:
v4hn 2017-03-01 16:27:20 +01:00
parent a1ef95300c
commit cd6f2d74da
2 changed files with 8 additions and 2 deletions

View File

@ -24,6 +24,7 @@ MOVEIT_CLASS_FORWARD(Task);
class Task {
public:
Task();
~Task();
void addStart( SubTaskPtr );
void addAfter( SubTaskPtr );

View File

@ -6,8 +6,7 @@
#include <moveit_msgs/GetPlanningScene.h>
#include <moveit/robot_model_loader/robot_model_loader.h>
moveit::task_constructor::Task::Task()
{
moveit::task_constructor::Task::Task(){
rml_.reset(new robot_model_loader::RobotModelLoader);
if( !rml_->getModel() )
throw Exception("Task failed to construct RobotModel");
@ -39,6 +38,12 @@ moveit::task_constructor::Task::Task()
scene_->setPlanningSceneMsg(res.scene);
}
moveit::task_constructor::Task::~Task(){
subtasks_.clear();
scene_.reset();
}
void moveit::task_constructor::Task::addStart( SubTaskPtr subtask ){
subtasks_.clear();
addSubTask( subtask );