39 #include <class_loader/class_loader.hpp>
43 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit_ros.resolve_constraint_frames");
52 void initialize(
const rclcpp::Node::SharedPtr& ,
const std::string& )
override
58 return "Resolve constraint frames to robot links";
63 std::vector<std::size_t>& )
const override
68 for (moveit_msgs::msg::Constraints& constraint : modified.goal_constraints)
ResolveConstraintFrames()
bool adaptAndPlan(const PlannerFn &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res, std::vector< std::size_t > &) const override
Adapt the planning request if needed, call the planner function planner and update the planning respo...
std::string getDescription() const override
Get a short string that identifies the planning request adapter.
void initialize(const rclcpp::Node::SharedPtr &, const std::string &) override
Initialize parameters using the passed Node and parameter namespace. If no initialization is needed,...
std::function< bool(const planning_scene::PlanningSceneConstPtr &, const planning_interface::MotionPlanRequest &, planning_interface::MotionPlanResponse &)> PlannerFn
bool resolveConstraintFrames(const moveit::core::RobotState &state, moveit_msgs::msg::Constraints &constraints)
Resolves frames used in constraints to links in the robot model.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
Generic interface to adapting motion planning requests.
This namespace includes the central class for representing planning contexts.
const rclcpp::Logger LOGGER
CLASS_LOADER_REGISTER_CLASS(default_planner_request_adapters::ResolveConstraintFrames, planning_request_adapter::PlanningRequestAdapter)