22#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
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)
49 getLogger(),
"[CbMoveEndEfector] new thread started to move absolute end effector");
50 moveit::planning_interface::MoveGroupInterface move_group(
getNode(), *
group_);
52 RCLCPP_DEBUG(
getLogger(),
"[CbMoveEndEfector] to move absolute end effector thread destroyed");
57 getLogger(),
"[CbMoveEndEfector] new thread started to move absolute end effector");
59 RCLCPP_DEBUG(
getLogger(),
"[CbMoveEndEfector] to move absolute end effector thread destroyed");
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) ==
82 moveit::planning_interface::MoveItErrorCode::SUCCESS);
84 getLogger(),
"[CbMoveEndEffector] Success Visualizing plan 1 (pose goal) %s",
85 success ?
"" :
"FAILED");
89 auto executionResult = moveGroupInterface.execute(computedMotionPlan);
91 if (executionResult == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
93 RCLCPP_INFO(
getLogger(),
"[CbMoveEndEffector] motion execution succeeded");
99 RCLCPP_INFO(
getLogger(),
"[CbMoveEndEffector] motion execution failed");
106 RCLCPP_INFO(
getLogger(),
"[CbMoveEndEffector] motion execution failed");
111 RCLCPP_DEBUG(
getLogger(),
"[CbMoveEndEffector] Synchronous sleep of 1 seconds");
112 rclcpp::sleep_for(500ms);
virtual void onEntry() override
ClMoveGroup * movegroupClient_
bool moveToAbsolutePose(moveit::planning_interface::MoveGroupInterface &moveGroupInterface, geometry_msgs::msg::PoseStamped &targetObjectPose)
geometry_msgs::msg::PoseStamped targetPose
std::optional< std::string > group_
std::shared_ptr< moveit::planning_interface::MoveGroupInterface > moveGroupClientInterface
void postEventMotionExecutionFailed()
void postEventMotionExecutionSucceded()
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
void requiresClient(SmaccClientType *&storage)