41#include <class_loader/class_loader.hpp>
42#include <rclcpp/logging.hpp>
43#include <rclcpp/node.hpp>
46#include <default_request_adapter_parameters.hpp>
61 return std::string(
"CheckForStackedConstraints");
69 if (req.path_constraints.position_constraints.size() > 1 || req.path_constraints.orientation_constraints.size() > 1)
71 RCLCPP_WARN(logger_,
"More than one PATH constraint is set. If your planning group does not have multiple end "
72 "effectors/arms, this is "
73 "unusual. Are you using a move_group_interface and forgetting to call clearPoseTargets() or "
76 for (
const auto& constraint : req.goal_constraints)
78 if (constraint.position_constraints.size() > 1 || constraint.orientation_constraints.size() > 1)
81 "More than one GOAL constraint is set. If your move_group does not have multiple end "
82 "effectors/arms, this is "
83 "unusual. Are you using a move_group_interface and forgetting to call clearPoseTargets() or "
92 std::unique_ptr<default_request_adapter_parameters::ParamListener> param_listener_;
93 rclcpp::Logger logger_;
Check if the motion plan request contains stacked path or goal constraints.
moveit::core::MoveItErrorCode adapt(const planning_scene::PlanningSceneConstPtr &, planning_interface::MotionPlanRequest &req) const override
Adapt the planning request.
std::string getDescription() const override
Get a description of this adapter.
CheckForStackedConstraints()
a wrapper around moveit_msgs::MoveItErrorCodes to make it easier to return an error code message from...
Concept in MoveIt which can be used to modify the planning problem(pre-processing) in a planning pipe...
Main namespace for MoveIt.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
CLASS_LOADER_REGISTER_CLASS(default_planning_request_adapters::ResolveConstraintFrames, planning_interface::PlanningRequestAdapter)