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");
98 RCLCPP_INFO(
getLogger(),
"[CbMoveEndEffector] motion execution failed");
105 RCLCPP_INFO(
getLogger(),
"[CbMoveEndEffector] motion execution failed");
110 RCLCPP_DEBUG(
getLogger(),
"[CbMoveEndEffector] Synchronous sleep of 1 seconds");
111 rclcpp::sleep_for(500ms);