From b6c778aa006bf8fc74c5ef091209cf9c37f52184 Mon Sep 17 00:00:00 2001 From: David Tiede <david.tiede@mailbox.tu-dresden.de> Date: Tue, 19 Oct 2021 16:52:34 +0200 Subject: [PATCH] Replace computeCartesianPath --- adapter_package/src/adapter_package.cpp | 10 ++-------- 1 file changed, 2 insertions(+), 8 deletions(-) diff --git a/adapter_package/src/adapter_package.cpp b/adapter_package/src/adapter_package.cpp index 4b37a9d..ac45da7 100644 --- a/adapter_package/src/adapter_package.cpp +++ b/adapter_package/src/adapter_package.cpp @@ -38,20 +38,14 @@ void move_toCallback(const std_msgs::String::ConstPtr& msg) std::string strA ("A"); std::string strB ("B"); if (strA == msg->data) { - waypoints.push_back(target_pose_1); + group.setPoseTarget(target_pose_1); } else if (strB == msg->data) { - waypoints.push_back(target_pose_2); + group.setPoseTarget(target_pose_2); } else { ROS_WARN("ADAPTER PACKAGE: Wrong message."); return; } - ///moveit::planning_interface::MoveGroupInterface::Plan plan; - //moveit_msgs::RobotTrajectory trajectory_msg; - //group.computeCartesianPath(waypoints, 0.01, 0.0, trajectory_msg, true); - //plan.trajectory_ = trajectory_msg; - //group.execute(plan); - group.setPoseTarget(target_pose_2); group.move(); ROS_INFO("ADAPTER PACKAGE: Finished movement."); -- GitLab