93 {
95 {
96 RCLCPP_WARN(
getLogger(),
"[CbMoveJoints] No joint value specified. Skipping planning call.");
99 return;
100 }
101
102
103 CpMotionPlanner * motionPlanner = nullptr;
105
106 bool success = false;
107 moveit::planning_interface::MoveGroupInterface::Plan computedMotionPlan;
108
109 if (motionPlanner != nullptr)
110 {
111
112 RCLCPP_INFO(
getLogger(),
"[CbMoveJoints] Using CpMotionPlanner component for joint planning");
113
114 PlanningOptions options;
116 {
118 }
119
121
122 success = result.success;
123 if (success)
124 {
125 computedMotionPlan = result.plan;
126 RCLCPP_INFO(
getLogger(),
"[CbMoveJoints] Planning succeeded (via CpMotionPlanner)");
127 }
128 else
129 {
130 RCLCPP_WARN(
131 getLogger(),
"[CbMoveJoints] Planning failed (via CpMotionPlanner): %s",
132 result.errorMessage.c_str());
133 }
134 }
135 else
136 {
137
138 RCLCPP_WARN(
140 "[CbMoveJoints] CpMotionPlanner component not available, using legacy planning "
141 "(consider adding CpMotionPlanner component)");
142
144
146
147 auto result = moveGroupInterface.plan(computedMotionPlan);
148
149 success = (result == moveit::core::MoveItErrorCode::SUCCESS);
150
151 RCLCPP_INFO(
152 getLogger(),
"[CbMoveJoints] Planning %s (legacy mode, code: %d)",
153 success ? "SUCCESS" : "FAILED", result.val);
154 }
155
156
157 if (success)
158 {
159
160 CpTrajectoryExecutor * trajectoryExecutor = nullptr;
162
163 bool executionSuccess = false;
164
165 if (trajectoryExecutor != nullptr)
166 {
167
168 RCLCPP_INFO(
169 getLogger(),
"[CbMoveJoints] Using CpTrajectoryExecutor component for execution");
170
171 ExecutionOptions execOptions;
172 execOptions.trajectoryName = this->
getName();
174 {
176 }
177
178 auto execResult = trajectoryExecutor->executePlan(computedMotionPlan, execOptions);
179 executionSuccess = execResult.success;
180
181 if (executionSuccess)
182 {
183 RCLCPP_INFO(
getLogger(),
"[CbMoveJoints] Execution succeeded (via CpTrajectoryExecutor)");
184 }
185 else
186 {
187 RCLCPP_WARN(
188 getLogger(),
"[CbMoveJoints] Execution failed (via CpTrajectoryExecutor): %s",
189 execResult.errorMessage.c_str());
190 }
191 }
192 else
193 {
194
195 RCLCPP_WARN(
197 "[CbMoveJoints] CpTrajectoryExecutor component not available, using legacy execution "
198 "(consider adding CpTrajectoryExecutor component)");
199
200 auto executionResult = moveGroupInterface.execute(computedMotionPlan);
201 executionSuccess = (executionResult == moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
202
203 RCLCPP_INFO(
204 getLogger(),
"[CbMoveJoints] Execution %s (legacy mode)",
205 executionSuccess ? "succeeded" : "failed");
206 }
207
208
209 if (executionSuccess)
210 {
211 RCLCPP_INFO_STREAM(
213 "[" << this->
getName() <<
"] motion execution succeeded. Throwing success event.");
216 }
217 else
218 {
219 RCLCPP_WARN_STREAM(
220 getLogger(),
"[" << this->
getName() <<
"] motion execution failed. Throwing fail event.");
223 }
224 }
225 else
226 {
228 RCLCPP_WARN_STREAM(
229 getLogger(),
"[" << this->
getName() <<
"] planning failed. Throwing fail event."
230 << std::endl
231 << statestr);
234 }
235 }
static std::string currentJointStatesToString(moveit::planning_interface::MoveGroupInterface &moveGroupInterface, std::map< std::string, double > &targetJoints)
std::optional< double > scalingFactor_
ClMoveit2z * movegroupClient_
void postEventMotionExecutionFailed()
void postEventMotionExecutionSucceded()
std::string getName() const
void requiresComponent(SmaccComponentType *&storage, bool throwExceptionIfNotExist)
virtual rclcpp::Logger getLogger() const