38 #include <class_loader/class_loader.hpp>
44 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit_ros.add_traj_smoothing");
54 void initialize(
const rclcpp::Node::SharedPtr& ,
const std::string& )
override
60 return "Add Ruckig trajectory smoothing.";
65 std::vector<std::size_t>& )
const override
70 if (!smoother_.applySmoothing(*res.
trajectory_, req.max_velocity_scaling_factor,
71 req.max_acceleration_scaling_factor))
This adapter uses the time-optimal trajectory generation method.
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...
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::string getDescription() const override
Get a short string that identifies the planning request adapter.
AddRuckigTrajectorySmoothing()
std::function< bool(const planning_scene::PlanningSceneConstPtr &, const planning_interface::MotionPlanRequest &, planning_interface::MotionPlanResponse &)> PlannerFn
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
robot_trajectory::RobotTrajectoryPtr trajectory_
CLASS_LOADER_REGISTER_CLASS(trajopt_interface::TrajOptPlannerManager, planning_interface::PlannerManager)