Task: move constructor

This commit is contained in:
Robert Haschke 2018-04-06 14:36:56 +02:00
parent 70065c98e7
commit 7ebc4b2c7e
4 changed files with 27 additions and 3 deletions

View File

@ -197,7 +197,7 @@ protected:
Stage(const Stage&) = delete;
protected:
StagePrivate* const pimpl_; // constness guarantees one initial write
StagePrivate* pimpl_;
};
std::ostream& operator<<(std::ostream& os, const Stage& stage);

View File

@ -64,12 +64,13 @@ MOVEIT_CLASS_FORWARD(Task)
*/
class Task : protected WrapperBase {
public:
Task(const std::string& id = "",
Stage::pointer &&container = std::make_unique<SerialContainer>("task pipeline"));
static planning_pipeline::PlanningPipelinePtr createPlanner(const moveit::core::RobotModelConstPtr &model,
const std::string &ns = "move_group",
const std::string &planning_plugin_param_name = "planning_plugin",
const std::string &adapter_plugins_param_name = "request_adapters");
Task(const std::string& id = "",
Stage::pointer &&container = std::make_unique<SerialContainer>("task pipeline"));
Task(Task &&other);
~Task();
std::string id() const;

View File

@ -64,6 +64,16 @@ Task::Task(const std::string& id, ContainerBase::pointer &&container)
enableIntrospection(true);
}
Task::Task(Task&& other)
: WrapperBase(std::string(), std::make_unique<SerialContainer>())
, id_(std::move(other.id_))
, robot_model_(std::move(other.robot_model_))
, introspection_(std::move(other.introspection_))
, task_cbs_(std::move(other.task_cbs_))
{
std::swap(pimpl_, other.pimpl_);
}
planning_pipeline::PlanningPipelinePtr
Task::createPlanner(const robot_model::RobotModelConstPtr& model, const std::string& ns,
const std::string& planning_plugin_param_name,

View File

@ -1,5 +1,6 @@
#include <moveit/task_constructor/container_p.h>
#include <moveit/task_constructor/stage_p.h>
#include <moveit/task_constructor/task.h>
#include "gtest_value_printers.h"
#include <gtest/gtest.h>
@ -450,3 +451,15 @@ TEST_F(ParallelTest, init_mismatching) {
EXPECT_INIT_FAILURE(false, true, BOTH, GEN);
EXPECT_INIT_FAILURE(true, true, BOTH, GEN);
}
TEST(Task, move) {
Task t1("foo");
t1.add(std::make_unique<GeneratorMockup>());
t1.add(std::make_unique<GeneratorMockup>());
EXPECT_EQ(t1.stages()->numChildren(), 2);
Task t2 = std::move(t1);
EXPECT_EQ(t2.stages()->numChildren(), 2);
EXPECT_EQ(t1.stages()->numChildren(), 0);
}