43#include <class_loader/class_loader.hpp>
58 return std::string(
"ResolveConstraintFrames");
68 for (moveit_msgs::msg::Constraints& constraint : req.goal_constraints)
76 rclcpp::Logger logger_;
Transforms frames used in constraints to link frames in the robot model.
std::string getDescription() const override
Get a description of this adapter.
ResolveConstraintFrames()
moveit::core::MoveItErrorCode adapt(const planning_scene::PlanningSceneConstPtr &planning_scene, planning_interface::MotionPlanRequest &req) const override
Adapt the planning request.
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...
bool resolveConstraintFrames(const moveit::core::RobotState &state, moveit_msgs::msg::Constraints &constraints)
Resolves frames used in constraints to links in the robot model.
Main namespace for MoveIt.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
This namespace includes the central class for representing planning contexts.
CLASS_LOADER_REGISTER_CLASS(default_planning_request_adapters::ResolveConstraintFrames, planning_interface::PlanningRequestAdapter)