Skip to content

Commit e923fbc

Browse files
JafarAbdirhaschke
andauthored
Fix Task's move constructor (#371)
* Add unit test * Fix TaskPrivate's move assignment operator * Slightly simplify code Co-authored-by: Robert Haschke <[email protected]>
1 parent 60229db commit e923fbc

File tree

2 files changed

+37
-6
lines changed

2 files changed

+37
-6
lines changed

core/src/task.cpp

Lines changed: 8 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -77,10 +77,12 @@ TaskPrivate::TaskPrivate(Task* me, const std::string& ns)
7777
TaskPrivate& TaskPrivate::operator=(TaskPrivate&& other) {
7878
this->WrapperBasePrivate::operator=(std::move(other));
7979
ns_ = std::move(other.ns_);
80-
introspection_ = std::move(other.introspection_);
8180
robot_model_ = std::move(other.robot_model_);
8281
robot_model_loader_ = std::move(other.robot_model_loader_);
8382
task_cbs_ = std::move(other.task_cbs_);
83+
// Ensure same introspection status, but keep the existing introspection instance,
84+
// which stores this task pointer and includes it in its task_id_
85+
static_cast<Task*>(me_)->enableIntrospection(static_cast<bool>(other.introspection_));
8486
return *this;
8587
}
8688

@@ -209,17 +211,17 @@ void Task::init() {
209211
stages()->pimpl()->resolveInterface(InterfaceFlags({ GENERATE }));
210212

211213
// provide introspection instance to all stages
212-
impl->setIntrospection(impl->introspection_.get());
214+
auto* introspection = impl->introspection_.get();
213215
impl->traverseStages(
214-
[impl](Stage& stage, int /*depth*/) {
215-
stage.pimpl()->setIntrospection(impl->introspection_.get());
216+
[introspection](Stage& stage, int /*depth*/) {
217+
stage.pimpl()->setIntrospection(introspection);
216218
return true;
217219
},
218220
1, UINT_MAX);
219221

220222
// first time publish task
221-
if (impl->introspection_)
222-
impl->introspection_->publishTaskDescription();
223+
if (introspection)
224+
introspection->publishTaskDescription();
223225
}
224226

225227
bool Task::canCompute() const {

core/test/test_move_to.cpp

Lines changed: 29 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,5 @@
11
#include "models.h"
2+
#include "stage_mockups.h"
23

34
#include <moveit/task_constructor/task.h>
45
#include <moveit/task_constructor/stages/move_to.h>
@@ -160,6 +161,34 @@ TEST_F(PandaMoveTo, poseIKFrameAttachedSubframeTarget) {
160161
}
161162
#endif
162163

164+
// This test require a running rosmaster
165+
TEST(Task, taskMoveConstructor) {
166+
auto create_task = [] {
167+
moveit::core::RobotModelConstPtr robot_model = getModel();
168+
Task t("first");
169+
t.setRobotModel(robot_model);
170+
auto ref = new stages::FixedState("fixed");
171+
auto scene = std::make_shared<planning_scene::PlanningScene>(t.getRobotModel());
172+
ref->setState(scene);
173+
174+
t.add(Stage::pointer(ref));
175+
t.add(std::make_unique<ConnectMockup>());
176+
t.add(std::make_unique<MonitoringGeneratorMockup>(ref));
177+
return t;
178+
};
179+
180+
// Segfaults when introspection is enabled
181+
Task t;
182+
t = create_task();
183+
184+
try {
185+
t.init();
186+
EXPECT_TRUE(t.plan(1));
187+
} catch (const InitStageException& e) {
188+
ADD_FAILURE() << "InitStageException:" << std::endl << e << t;
189+
}
190+
}
191+
163192
int main(int argc, char** argv) {
164193
testing::InitGoogleTest(&argc, argv);
165194
ros::init(argc, argv, "move_to_test");

0 commit comments

Comments
 (0)