23#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
25#include <tf2/impl/utils.h>
29using namespace std::chrono_literals;
36 geometry_msgs::msg::PoseStamped target_pose, std::string tip_link)
37: targetPose(target_pose)
42void CbMoveEndEffector::onEntry()
44 this->requiresClient(movegroupClient_);
49 getLogger(),
"[CbMoveEndEfector] new thread started to move absolute end effector");
50 moveit::planning_interface::MoveGroupInterface move_group(getNode(), *group_);
51 this->moveToAbsolutePose(move_group, targetPose);
52 RCLCPP_DEBUG(getLogger(),
"[CbMoveEndEfector] to move absolute end effector thread destroyed");
57 getLogger(),
"[CbMoveEndEfector] new thread started to move absolute end effector");
58 this->moveToAbsolutePose(*(movegroupClient_->moveGroupClientInterface), targetPose);
59 RCLCPP_DEBUG(getLogger(),
"[CbMoveEndEfector] to move absolute end effector thread destroyed");
63bool CbMoveEndEffector::moveToAbsolutePose(
64 moveit::planning_interface::MoveGroupInterface & moveGroupInterface,
65 geometry_msgs::msg::PoseStamped & targetObjectPose)
68 RCLCPP_DEBUG(getLogger(),
"[CbMoveEndEffector] Synchronous sleep of 1 seconds");
69 rclcpp::sleep_for(500ms);
71 moveGroupInterface.setPlanningTime(1.0);
74 getLogger(),
"[CbMoveEndEffector] Target End efector Pose: " << targetObjectPose);
76 moveGroupInterface.setPoseTarget(targetObjectPose, tip_link_);
77 moveGroupInterface.setPoseReferenceFrame(targetObjectPose.header.frame_id);
79 moveit::planning_interface::MoveGroupInterface::Plan computedMotionPlan;
81 (moveGroupInterface.plan(computedMotionPlan) == moveit::core::MoveItErrorCode::SUCCESS);
83 getLogger(),
"[CbMoveEndEffector] Success Visualizing plan 1 (pose goal) %s",
84 success ?
"" :
"FAILED");
88 auto executionResult = moveGroupInterface.execute(computedMotionPlan);
90 if (executionResult == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
92 RCLCPP_INFO(getLogger(),
"[CbMoveEndEffector] motion execution succeeded");
93 movegroupClient_->postEventMotionExecutionSucceded();
94 this->postSuccessEvent();
98 RCLCPP_INFO(getLogger(),
"[CbMoveEndEffector] motion execution failed");
99 movegroupClient_->postEventMotionExecutionFailed();
100 this->postFailureEvent();
105 RCLCPP_INFO(getLogger(),
"[CbMoveEndEffector] motion execution failed");
106 movegroupClient_->postEventMotionExecutionFailed();
107 this->postFailureEvent();
110 RCLCPP_DEBUG(getLogger(),
"[CbMoveEndEffector] Synchronous sleep of 1 seconds");
111 rclcpp::sleep_for(500ms);