21#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
22#include <geometry_msgs/msg/quaternion_stamped.hpp>
25#include <tf2/impl/utils.h>
26#include <tf2/transform_datatypes.h>
37: transform_(transform)
45 "[CbMoveEndEffectorRelative] Transform end effector pose relative: " <<
transform_);
51 moveit::planning_interface::MoveGroupInterface move_group(
52 getNode(), moveit::planning_interface::MoveGroupInterface::Options(*(this->
group_)));
64 moveit::planning_interface::MoveGroupInterface & moveGroupInterface,
65 geometry_msgs::msg::Transform & transformOffset)
67 auto referenceStartPose = moveGroupInterface.getCurrentPose();
68 tf2::Quaternion currentOrientation;
69 tf2::convert(referenceStartPose.pose.orientation, currentOrientation);
70 tf2::Quaternion desiredRelativeRotation;
72 tf2::convert(transformOffset.rotation, desiredRelativeRotation);
74 auto targetOrientation = desiredRelativeRotation * currentOrientation;
76 geometry_msgs::msg::PoseStamped targetObjectPose = referenceStartPose;
78 targetObjectPose.pose.orientation = tf2::toMsg(targetOrientation);
79 targetObjectPose.pose.position.x += transformOffset.translation.x;
80 targetObjectPose.pose.position.y += transformOffset.translation.y;
81 targetObjectPose.pose.position.z += transformOffset.translation.z;
83 moveGroupInterface.setPlanningTime(1.0);
86 getLogger(),
"[CbMoveEndEffectorRelative] Target End efector Pose: " << targetObjectPose);
88 moveGroupInterface.setPoseTarget(targetObjectPose);
89 moveGroupInterface.setPoseReferenceFrame(
"map");
91 moveit::planning_interface::MoveGroupInterface::Plan computedMotionPlan;
93 (moveGroupInterface.plan(computedMotionPlan) ==
94 moveit::planning_interface::MoveItErrorCode::SUCCESS);
95 RCLCPP_INFO(
getLogger(),
"Success Visualizing plan 1 (pose goal) %s", success ?
"" :
"FAILED");
99 auto executionResult = moveGroupInterface.execute(computedMotionPlan);
101 if (executionResult == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
103 RCLCPP_INFO(
getLogger(),
"[CbMoveEndEffectorRelative] motion execution succeeded");
109 moveGroupInterface.setPoseTarget(
111 RCLCPP_INFO(
getLogger(),
"[CbMoveEndEffectorRelative] motion execution failed");
118 moveGroupInterface.setPoseTarget(
120 RCLCPP_INFO(
getLogger(),
"[CbMoveEndEffectorRelative] motion execution failed");
virtual void onExit() override
void moveRelative(moveit::planning_interface::MoveGroupInterface &moveGroupinterface, geometry_msgs::msg::Transform &transformOffset)
virtual void onEntry() override
geometry_msgs::msg::Transform transform_
std::optional< std::string > group_
CbMoveEndEffectorRelative()
ClMoveGroup * movegroupClient_
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)