78 {
79 RCLCPP_DEBUG(
getLogger(),
"[CbMoveEndEffector] Synchronous sleep of 1 seconds");
80 rclcpp::sleep_for(500ms);
81
82
83 CpMotionPlanner * motionPlanner = nullptr;
85
86 bool success = false;
87 moveit::planning_interface::MoveGroupInterface::Plan computedMotionPlan;
88
89 RCLCPP_INFO_STREAM(
90 getLogger(),
"[CbMoveEndEffector] Target End effector Pose: " << targetObjectPose);
91
92 if (motionPlanner != nullptr)
93 {
94
95 RCLCPP_INFO(
getLogger(),
"[CbMoveEndEffector] Using CpMotionPlanner component for planning");
96
97 PlanningOptions options;
98 options.planningTime = 1.0;
99 options.poseReferenceFrame = targetObjectPose.header.frame_id;
100
101 std::optional<std::string> tipLinkOpt;
103 {
105 }
106
107 auto result = motionPlanner->planToPose(targetObjectPose, tipLinkOpt, options);
108
109 success = result.success;
110 if (success)
111 {
112 computedMotionPlan = result.plan;
113 RCLCPP_INFO(
getLogger(),
"[CbMoveEndEffector] Planning succeeded (via CpMotionPlanner)");
114 }
115 else
116 {
117 RCLCPP_WARN(
118 getLogger(),
"[CbMoveEndEffector] Planning failed (via CpMotionPlanner): %s",
119 result.errorMessage.c_str());
120 }
121 }
122 else
123 {
124
125 RCLCPP_WARN(
127 "[CbMoveEndEffector] CpMotionPlanner component not available, using legacy planning "
128 "(consider adding CpMotionPlanner component)");
129
130 moveGroupInterface.setPlanningTime(1.0);
131 moveGroupInterface.setPoseTarget(targetObjectPose,
tip_link_);
132 moveGroupInterface.setPoseReferenceFrame(targetObjectPose.header.frame_id);
133
134 success =
135 (moveGroupInterface.plan(computedMotionPlan) == moveit::core::MoveItErrorCode::SUCCESS);
136 RCLCPP_INFO(
137 getLogger(),
"[CbMoveEndEffector] Planning %s (legacy mode)",
138 success ? "succeeded" : "FAILED");
139 }
140
141
142 if (success)
143 {
144
145 CpTrajectoryExecutor * trajectoryExecutor = nullptr;
147
148 bool executionSuccess = false;
149
150 if (trajectoryExecutor != nullptr)
151 {
152
153 RCLCPP_INFO(
154 getLogger(),
"[CbMoveEndEffector] Using CpTrajectoryExecutor component for execution");
155
156 ExecutionOptions execOptions;
157 execOptions.trajectoryName = this->
getName();
158
159 auto execResult = trajectoryExecutor->executePlan(computedMotionPlan, execOptions);
160 executionSuccess = execResult.success;
161
162 if (executionSuccess)
163 {
164 RCLCPP_INFO(
165 getLogger(),
"[CbMoveEndEffector] Execution succeeded (via CpTrajectoryExecutor)");
166 }
167 else
168 {
169 RCLCPP_WARN(
170 getLogger(),
"[CbMoveEndEffector] Execution failed (via CpTrajectoryExecutor): %s",
171 execResult.errorMessage.c_str());
172 }
173 }
174 else
175 {
176
177 RCLCPP_WARN(
179 "[CbMoveEndEffector] CpTrajectoryExecutor component not available, using legacy "
180 "execution "
181 "(consider adding CpTrajectoryExecutor component)");
182
183 auto executionResult = moveGroupInterface.execute(computedMotionPlan);
184 executionSuccess = (executionResult == moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
185
186 RCLCPP_INFO(
187 getLogger(),
"[CbMoveEndEffector] Execution %s (legacy mode)",
188 executionSuccess ? "succeeded" : "failed");
189 }
190
191
192 if (executionSuccess)
193 {
196 }
197 else
198 {
201 }
202 }
203 else
204 {
205 RCLCPP_INFO(
getLogger(),
"[CbMoveEndEffector] planning failed, skipping execution");
208 }
209
210 RCLCPP_DEBUG(
getLogger(),
"[CbMoveEndEffector] Synchronous sleep of 1 seconds");
211 rclcpp::sleep_for(500ms);
212
213 return success;
214 }
ClMoveit2z * movegroupClient_
void postEventMotionExecutionFailed()
void postEventMotionExecutionSucceded()
std::string getName() const
void requiresComponent(SmaccComponentType *&storage, bool throwExceptionIfNotExist)
virtual rclcpp::Logger getLogger() const