SMACC2
Loading...
Searching...
No Matches
cp_motion_planner.hpp
Go to the documentation of this file.
1// Copyright 2021 RobosoftAI Inc.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15/*****************************************************************************************************************
16 *
17 * Authors: Pablo Inigo Blasco, Brett Aldrich
18 *
19 *****************************************************************************************************************/
20
21#pragma once
22
23#include <smacc2/component.hpp>
24
26
27#include <moveit/move_group_interface/move_group_interface.h>
28#include <geometry_msgs/msg/pose_stamped.hpp>
29#include <moveit_msgs/msg/move_it_error_codes.hpp>
30#include <moveit_msgs/msg/robot_trajectory.hpp>
31
32#include <map>
33#include <optional>
34#include <string>
35
36namespace cl_moveit2z
37{
42{
43 std::optional<double> planningTime;
44 std::optional<double> maxVelocityScaling;
45 std::optional<double> maxAccelerationScaling;
46 std::optional<std::string> planningPipelineId;
47 std::optional<std::string> plannerId;
48 std::optional<std::string> poseReferenceFrame;
49};
50
55{
56 bool success;
57 moveit::planning_interface::MoveGroupInterface::Plan plan;
58 moveit::core::MoveItErrorCode errorCode;
59 std::string errorMessage;
60
62 : success(false), errorCode(moveit::core::MoveItErrorCode::FAILURE), errorMessage("")
63 {
64 }
65};
66
80{
81public:
82 CpMotionPlanner() = default;
83 virtual ~CpMotionPlanner() = default;
84
88 inline void onInitialize() override
89 {
91 RCLCPP_INFO(getLogger(), "[CpMotionPlanner] Component initialized");
92 }
93
103 const geometry_msgs::msg::PoseStamped & target,
104 const std::optional<std::string> & tipLink = std::nullopt, const PlanningOptions & options = {})
105 {
106 PlanningResult result;
107
108 if (!moveit2zClient_)
109 {
110 result.errorMessage = "ClMoveit2z client not available";
111 RCLCPP_ERROR(getLogger(), "[CpMotionPlanner] %s", result.errorMessage.c_str());
112 return result;
113 }
114
115 auto & moveGroup = moveit2zClient_->moveGroupClientInterface;
116
117 try
118 {
119 // Apply planning options
120 applyPlanningOptions(*moveGroup, options);
121
122 // Set pose target
123 if (tipLink && !tipLink->empty())
124 {
125 moveGroup->setPoseTarget(target, *tipLink);
126 }
127 else
128 {
129 moveGroup->setPoseTarget(target);
130 }
131
132 // Set reference frame if specified
133 if (options.poseReferenceFrame)
134 {
135 moveGroup->setPoseReferenceFrame(*options.poseReferenceFrame);
136 }
137 else if (!target.header.frame_id.empty())
138 {
139 moveGroup->setPoseReferenceFrame(target.header.frame_id);
140 }
141
142 RCLCPP_INFO(getLogger(), "[CpMotionPlanner] Planning to pose...");
143
144 // Plan
145 result.errorCode = moveGroup->plan(result.plan);
146 result.success = (result.errorCode == moveit::core::MoveItErrorCode::SUCCESS);
147
148 if (result.success)
149 {
150 RCLCPP_INFO(getLogger(), "[CpMotionPlanner] Planning to pose succeeded");
151 }
152 else
153 {
154 result.errorMessage =
155 "Planning to pose failed with error code: " + std::to_string(result.errorCode.val);
156 RCLCPP_WARN(getLogger(), "[CpMotionPlanner] %s", result.errorMessage.c_str());
157 }
158 }
159 catch (const std::exception & e)
160 {
161 result.success = false;
162 result.errorMessage = std::string("Exception during planning: ") + e.what();
163 RCLCPP_ERROR(getLogger(), "[CpMotionPlanner] %s", result.errorMessage.c_str());
164 }
165
166 return result;
167 }
168
177 const std::map<std::string, double> & jointTargets, const PlanningOptions & options = {})
178 {
179 PlanningResult result;
180
181 if (!moveit2zClient_)
182 {
183 result.errorMessage = "ClMoveit2z client not available";
184 RCLCPP_ERROR(getLogger(), "[CpMotionPlanner] %s", result.errorMessage.c_str());
185 return result;
186 }
187
188 if (jointTargets.empty())
189 {
190 result.errorMessage = "No joint targets specified";
191 RCLCPP_WARN(getLogger(), "[CpMotionPlanner] %s", result.errorMessage.c_str());
192 return result;
193 }
194
195 auto & moveGroup = moveit2zClient_->moveGroupClientInterface;
196
197 try
198 {
199 // Apply planning options
200 applyPlanningOptions(*moveGroup, options);
201
202 // Set joint value targets
203 moveGroup->setJointValueTarget(jointTargets);
204
205 RCLCPP_INFO(
206 getLogger(), "[CpMotionPlanner] Planning to joint configuration (%lu joints)...",
207 jointTargets.size());
208
209 // Plan
210 result.errorCode = moveGroup->plan(result.plan);
211 result.success = (result.errorCode == moveit::core::MoveItErrorCode::SUCCESS);
212
213 if (result.success)
214 {
215 RCLCPP_INFO(getLogger(), "[CpMotionPlanner] Planning to joint configuration succeeded");
216 }
217 else
218 {
219 result.errorMessage = "Planning to joint configuration failed with error code: " +
220 std::to_string(result.errorCode.val);
221 RCLCPP_WARN(getLogger(), "[CpMotionPlanner] %s", result.errorMessage.c_str());
222 }
223 }
224 catch (const std::exception & e)
225 {
226 result.success = false;
227 result.errorMessage = std::string("Exception during planning: ") + e.what();
228 RCLCPP_ERROR(getLogger(), "[CpMotionPlanner] %s", result.errorMessage.c_str());
229 }
230
231 return result;
232 }
233
244 const std::vector<geometry_msgs::msg::Pose> & waypoints, double maxStep = 0.01,
245 double jumpThreshold = 0.0, bool avoidCollisions = true)
246 {
247 PlanningResult result;
248
249 if (!moveit2zClient_)
250 {
251 result.errorMessage = "ClMoveit2z client not available";
252 RCLCPP_ERROR(getLogger(), "[CpMotionPlanner] %s", result.errorMessage.c_str());
253 return result;
254 }
255
256 if (waypoints.empty())
257 {
258 result.errorMessage = "No waypoints specified";
259 RCLCPP_WARN(getLogger(), "[CpMotionPlanner] %s", result.errorMessage.c_str());
260 return result;
261 }
262
263 auto & moveGroup = moveit2zClient_->moveGroupClientInterface;
264
265 try
266 {
267 RCLCPP_INFO(
268 getLogger(), "[CpMotionPlanner] Planning Cartesian path with %lu waypoints...",
269 waypoints.size());
270
271 moveit_msgs::msg::RobotTrajectory trajectory;
272 double fractionAchieved = moveGroup->computeCartesianPath(
273 waypoints, maxStep, jumpThreshold, trajectory, avoidCollisions);
274
275 result.plan.trajectory_ = trajectory;
276
277 // Consider successful if we achieved at least 95% of the path
278 result.success = (fractionAchieved >= 0.95);
279
280 if (result.success)
281 {
282 result.errorCode = moveit::core::MoveItErrorCode::SUCCESS;
283 RCLCPP_INFO(
284 getLogger(), "[CpMotionPlanner] Cartesian path planning succeeded (%.1f%% achieved)",
285 fractionAchieved * 100.0);
286 }
287 else
288 {
289 result.errorCode = moveit::core::MoveItErrorCode::PLANNING_FAILED;
290 result.errorMessage = "Cartesian path planning achieved only " +
291 std::to_string(fractionAchieved * 100.0) + "% of the path";
292 RCLCPP_WARN(getLogger(), "[CpMotionPlanner] %s", result.errorMessage.c_str());
293 }
294 }
295 catch (const std::exception & e)
296 {
297 result.success = false;
298 result.errorMessage = std::string("Exception during Cartesian path planning: ") + e.what();
299 RCLCPP_ERROR(getLogger(), "[CpMotionPlanner] %s", result.errorMessage.c_str());
300 }
301
302 return result;
303 }
304
311 inline moveit::core::RobotStatePtr getCurrentState(double waitTime = 1.0)
312 {
313 if (!moveit2zClient_)
314 {
315 RCLCPP_ERROR(getLogger(), "[CpMotionPlanner] ClMoveit2z client not available");
316 return nullptr;
317 }
318
319 auto & moveGroup = moveit2zClient_->moveGroupClientInterface;
320
321 try
322 {
323 return moveGroup->getCurrentState(waitTime);
324 }
325 catch (const std::exception & e)
326 {
327 RCLCPP_ERROR(getLogger(), "[CpMotionPlanner] Exception getting current state: %s", e.what());
328 return nullptr;
329 }
330 }
331
332private:
334
342 moveit::planning_interface::MoveGroupInterface & moveGroup, const PlanningOptions & options)
343 {
344 if (options.planningTime)
345 {
346 moveGroup.setPlanningTime(*options.planningTime);
347 }
348
349 if (options.maxVelocityScaling)
350 {
351 moveGroup.setMaxVelocityScalingFactor(*options.maxVelocityScaling);
352 }
353
354 if (options.maxAccelerationScaling)
355 {
356 moveGroup.setMaxAccelerationScalingFactor(*options.maxAccelerationScaling);
357 }
358
359 if (options.planningPipelineId)
360 {
361 moveGroup.setPlanningPipelineId(*options.planningPipelineId);
362 }
363
364 if (options.plannerId)
365 {
366 moveGroup.setPlannerId(*options.plannerId);
367 }
368 }
369};
370
371} // namespace cl_moveit2z
std::shared_ptr< moveit::planning_interface::MoveGroupInterface > moveGroupClientInterface
Component for centralized motion planning operations.
moveit::core::RobotStatePtr getCurrentState(double waitTime=1.0)
Get current robot state.
PlanningResult planToJointTarget(const std::map< std::string, double > &jointTargets, const PlanningOptions &options={})
Plan to joint values.
PlanningResult planToPose(const geometry_msgs::msg::PoseStamped &target, const std::optional< std::string > &tipLink=std::nullopt, const PlanningOptions &options={})
Plan to a Cartesian pose.
PlanningResult planCartesianPath(const std::vector< geometry_msgs::msg::Pose > &waypoints, double maxStep=0.01, double jumpThreshold=0.0, bool avoidCollisions=true)
Plan a Cartesian path.
void applyPlanningOptions(moveit::planning_interface::MoveGroupInterface &moveGroup, const PlanningOptions &options)
Apply planning options to MoveGroupInterface.
void onInitialize() override
Initialize the component and get reference to ClMoveit2z client.
virtual ~CpMotionPlanner()=default
void requiresClient(TClient *&requiredClientStorage)
rclcpp::Logger getLogger() const
Configuration options for motion planning.
std::optional< std::string > plannerId
std::optional< double > maxVelocityScaling
std::optional< std::string > poseReferenceFrame
std::optional< double > maxAccelerationScaling
std::optional< double > planningTime
std::optional< std::string > planningPipelineId
Result of a planning operation.
moveit::planning_interface::MoveGroupInterface::Plan plan
moveit::core::MoveItErrorCode errorCode