40 #include <class_loader/class_loader.hpp>
44 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit_ros.add_iterative_spline_parameterization");
53 void initialize(
const rclcpp::Node::SharedPtr& ,
const std::string& )
override
59 return "Add Time Parameterization";
64 std::vector<std::size_t>& )
const override
71 req.max_acceleration_scaling_factor))
73 RCLCPP_WARN(LOGGER,
"Time parametrization for the solution path failed.");
AddIterativeSplineParameterization()
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
This class sets the timestamps of a trajectory to enforce velocity, acceleration constraints....
bool computeTimeStamps(robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) const override
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
Generic interface to adapting motion planning requests.
This namespace includes the central class for representing planning contexts.
robot_trajectory::RobotTrajectoryPtr trajectory_
CLASS_LOADER_REGISTER_CLASS(trajopt_interface::TrajOptPlannerManager, planning_interface::PlannerManager)