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>
57 moveit::planning_interface::MoveGroupInterface::Plan
plan;
91 RCLCPP_INFO(
getLogger(),
"[CpMotionPlanner] Component initialized");
103 const geometry_msgs::msg::PoseStamped & target,
104 const std::optional<std::string> & tipLink = std::nullopt,
const PlanningOptions & options = {})
110 result.
errorMessage =
"ClMoveit2z client not available";
123 if (tipLink && !tipLink->empty())
125 moveGroup->setPoseTarget(target, *tipLink);
129 moveGroup->setPoseTarget(target);
133 if (options.poseReferenceFrame)
135 moveGroup->setPoseReferenceFrame(*options.poseReferenceFrame);
137 else if (!target.header.frame_id.empty())
139 moveGroup->setPoseReferenceFrame(target.header.frame_id);
142 RCLCPP_INFO(
getLogger(),
"[CpMotionPlanner] Planning to pose...");
146 result.
success = (result.
errorCode == moveit::core::MoveItErrorCode::SUCCESS);
150 RCLCPP_INFO(
getLogger(),
"[CpMotionPlanner] Planning to pose succeeded");
155 "Planning to pose failed with error code: " + std::to_string(result.
errorCode.val);
159 catch (
const std::exception & e)
162 result.
errorMessage = std::string(
"Exception during planning: ") + e.what();
177 const std::map<std::string, double> & jointTargets,
const PlanningOptions & options = {})
183 result.
errorMessage =
"ClMoveit2z client not available";
188 if (jointTargets.empty())
203 moveGroup->setJointValueTarget(jointTargets);
206 getLogger(),
"[CpMotionPlanner] Planning to joint configuration (%lu joints)...",
207 jointTargets.size());
211 result.
success = (result.
errorCode == moveit::core::MoveItErrorCode::SUCCESS);
215 RCLCPP_INFO(
getLogger(),
"[CpMotionPlanner] Planning to joint configuration succeeded");
219 result.
errorMessage =
"Planning to joint configuration failed with error code: " +
224 catch (
const std::exception & e)
227 result.
errorMessage = std::string(
"Exception during planning: ") + e.what();
244 const std::vector<geometry_msgs::msg::Pose> & waypoints,
double maxStep = 0.01,
245 double jumpThreshold = 0.0,
bool avoidCollisions =
true)
251 result.
errorMessage =
"ClMoveit2z client not available";
256 if (waypoints.empty())
268 getLogger(),
"[CpMotionPlanner] Planning Cartesian path with %lu waypoints...",
271 moveit_msgs::msg::RobotTrajectory trajectory;
272 double fractionAchieved = moveGroup->computeCartesianPath(
273 waypoints, maxStep, jumpThreshold, trajectory, avoidCollisions);
275 result.
plan.trajectory_ = trajectory;
278 result.
success = (fractionAchieved >= 0.95);
282 result.
errorCode = moveit::core::MoveItErrorCode::SUCCESS;
284 getLogger(),
"[CpMotionPlanner] Cartesian path planning succeeded (%.1f%% achieved)",
285 fractionAchieved * 100.0);
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";
295 catch (
const std::exception & e)
298 result.
errorMessage = std::string(
"Exception during Cartesian path planning: ") + e.what();
315 RCLCPP_ERROR(
getLogger(),
"[CpMotionPlanner] ClMoveit2z client not available");
323 return moveGroup->getCurrentState(waitTime);
325 catch (
const std::exception & e)
327 RCLCPP_ERROR(
getLogger(),
"[CpMotionPlanner] Exception getting current state: %s", e.what());
342 moveit::planning_interface::MoveGroupInterface & moveGroup,
const PlanningOptions & options)
366 moveGroup.setPlannerId(*options.
plannerId);
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.
CpMotionPlanner()=default
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.
ClMoveit2z * moveit2zClient_
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