9#include <tf/transform_datatypes.h>
25 ROS_INFO_STREAM(
"[CbMoveEndEffectorRelative] Transform end effector pose relative: " <<
transform_);
31 moveit::planning_interface::MoveGroupInterface move_group(*(this->
group_));
46 auto referenceStartPose = moveGroupInterface.getCurrentPose();
47 tf::Quaternion currentOrientation;
48 tf::quaternionMsgToTF(referenceStartPose.pose.orientation, currentOrientation);
49 tf::Quaternion desiredRelativeRotation;
51 tf::quaternionMsgToTF(transformOffset.rotation, desiredRelativeRotation);
53 auto targetOrientation = desiredRelativeRotation * currentOrientation;
55 geometry_msgs::PoseStamped targetObjectPose = referenceStartPose;
57 tf::quaternionTFToMsg(targetOrientation, targetObjectPose.pose.orientation);
58 targetObjectPose.pose.position.x += transformOffset.translation.x;
59 targetObjectPose.pose.position.y += transformOffset.translation.y;
60 targetObjectPose.pose.position.z += transformOffset.translation.z;
62 moveGroupInterface.setPlanningTime(1.0);
64 ROS_INFO_STREAM(
"[CbMoveEndEffectorRelative] Target End efector Pose: " << targetObjectPose);
66 moveGroupInterface.setPoseTarget(targetObjectPose);
67 moveGroupInterface.setPoseReferenceFrame(
"map");
69 moveit::planning_interface::MoveGroupInterface::Plan computedMotionPlan;
70 bool success = (moveGroupInterface.plan(computedMotionPlan) == moveit::core::MoveItErrorCode::SUCCESS);
71 ROS_INFO_NAMED(
"CbMoveEndEffectorRelative",
"Success Visualizing plan 1 (pose goal) %s", success ?
"" :
"FAILED");
75 auto executionResult = moveGroupInterface.execute(computedMotionPlan);
77 if (executionResult == moveit_msgs::MoveItErrorCodes::SUCCESS)
79 ROS_INFO(
"[CbMoveEndEffectorRelative] motion execution succeeded");
85 moveGroupInterface.setPoseTarget(referenceStartPose);
86 ROS_INFO(
"[CbMoveEndEffectorRelative] motion execution failed");
93 moveGroupInterface.setPoseTarget(referenceStartPose);
94 ROS_INFO(
"[CbMoveEndEffectorRelative] motion execution failed");
boost::optional< std::string > group_
virtual void onExit() override
virtual void onEntry() override
void moveRelative(moveit::planning_interface::MoveGroupInterface &moveGroupinterface, geometry_msgs::Transform &transformOffset)
CbMoveEndEffectorRelative()
ClMoveGroup * movegroupClient_
geometry_msgs::Transform transform_
void postEventMotionExecutionFailed()
moveit::planning_interface::MoveGroupInterface moveGroupClientInterface
void postEventMotionExecutionSucceded()
void requiresClient(SmaccClientType *&storage)