Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix task's move constructor #371

Merged
merged 4 commits into from
Jun 14, 2022
Merged
Show file tree
Hide file tree
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 0 additions & 1 deletion core/src/task.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,6 @@ TaskPrivate::TaskPrivate(Task* me, const std::string& ns)
TaskPrivate& TaskPrivate::operator=(TaskPrivate&& other) {
this->WrapperBasePrivate::operator=(std::move(other));
ns_ = std::move(other.ns_);
introspection_ = std::move(other.introspection_);
Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Maybe I should reset other.introspection_?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Moving a unique_ptr like this should correctly reset other's introspection_ pointer.

robot_model_ = std::move(other.robot_model_);
robot_model_loader_ = std::move(other.robot_model_loader_);
task_cbs_ = std::move(other.task_cbs_);
Expand Down
29 changes: 29 additions & 0 deletions core/test/test_move_to.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
#include "models.h"
#include "stage_mockups.h"

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

// This test require a running rosmaster
TEST(Task, taskMoveConstructor) {
auto create_task = [] {
moveit::core::RobotModelConstPtr robot_model = getModel();
Task t("first");
t.setRobotModel(robot_model);
auto ref = new stages::FixedState("fixed");
auto scene = std::make_shared<planning_scene::PlanningScene>(t.getRobotModel());
ref->setState(scene);

t.add(Stage::pointer(ref));
t.add(std::make_unique<ConnectMockup>());
t.add(std::make_unique<MonitoringGeneratorMockup>(ref));
return t;
};

// Segfaults when introspection is enabled
Task t;
t = create_task();

try {
t.init();
EXPECT_TRUE(t.plan(1));
} catch (const InitStageException& e) {
ADD_FAILURE() << "InitStageException:" << std::endl << e << t;
}
}

int main(int argc, char** argv) {
testing::InitGoogleTest(&argc, argv);
ros::init(argc, argv, "move_to_test");
Expand Down