From 02290aff452f5792a0e52e8631f2637d5095880f Mon Sep 17 00:00:00 2001 From: Niko Date: Mon, 4 Sep 2023 19:32:14 +0200 Subject: [PATCH] added moveit_interface --- src/moveit_interface.cpp | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/src/moveit_interface.cpp b/src/moveit_interface.cpp index 8cdb43f..3d20c2d 100644 --- a/src/moveit_interface.cpp +++ b/src/moveit_interface.cpp @@ -25,14 +25,17 @@ class MoveitInterface : public rclcpp::Node publisher_ = this->create_publisher("moveit_interface/joint_space_trajectory", 10); subcriber_ = this->create_subscription("moveit_interface/task_space_trajectory", 10, std::bind(&MoveitInterface::task_space_callback, this, std::placeholders::_1)); execute_sub_ = this->create_subscription("moveit_interface/execution", 10, std::bind(&MoveitInterface::execution_callback, this, std::placeholders::_1)); - + + // Create a shared instance of the current node + auto shared_this = std::shared_ptr(this); + // Connecting to moveit static const std::string PLANNING_GROUP = "panda_arm"; - move_group_ = std::make_shared(std::shared_ptr(std::move(this)), PLANNING_GROUP); + move_group_ = std::make_shared(std::shared_ptr(shared_this), PLANNING_GROUP); // const moveit::core::JointModelGroup* joint_model_group = move_group_->getCurrentState()->getJointModelGroup(PLANNING_GROUP); // Connection to Rviz - visual_tools_ = std::make_shared(std::shared_ptr(std::move(this)), "panda_link0", "move_group", move_group_->getRobotModel()); + visual_tools_ = std::make_shared(std::shared_ptr(shared_this), "panda_link0", "move_group", move_group_->getRobotModel()); Eigen::Isometry3d text_pose = Eigen::Isometry3d::Identity(); text_pose.translation().z()=1.0; visual_tools_->publishText(text_pose, "MoveGroupInterface_Demo", rviz_visual_tools::WHITE, rviz_visual_tools::XLARGE);