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) == moveit::core::MoveItErrorCode::SUCCESS);
94 RCLCPP_INFO(
getLogger(),
"Success Visualizing plan 1 (pose goal) %s", success ?
"" :
"FAILED");
98 auto executionResult = moveGroupInterface.execute(computedMotionPlan);
100 if (executionResult == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
102 RCLCPP_INFO(
getLogger(),
"[CbMoveEndEffectorRelative] motion execution succeeded");
108 moveGroupInterface.setPoseTarget(
110 RCLCPP_INFO(
getLogger(),
"[CbMoveEndEffectorRelative] motion execution failed");
117 moveGroupInterface.setPoseTarget(
119 RCLCPP_INFO(
getLogger(),
"[CbMoveEndEffectorRelative] motion execution failed");