39 #include <class_loader/class_loader.hpp>
42 #include <default_plan_request_adapter_parameters.hpp>
56 void initialize(
const rclcpp::Node::SharedPtr& node,
const std::string& parameter_namespace)
override
59 std::make_unique<default_plan_request_adapter_parameters::ParamListener>(node, parameter_namespace);
64 return "Add Time Optimal Parameterization";
74 RCLCPP_DEBUG(logger_,
" Running '%s'", getDescription().c_str());
75 const auto params = param_listener_->get_params();
79 RCLCPP_WARN(logger_,
" Time parametrization for the solution path failed.");
88 std::unique_ptr<default_plan_request_adapter_parameters::ParamListener>
param_listener_;
This adapter uses the time-optimal trajectory generation method.
std::string getDescription() const override
Get a description of this adapter.
AddTimeOptimalParameterization()
void initialize(const rclcpp::Node::SharedPtr &node, const std::string ¶meter_namespace) override
Initialize parameters using the passed Node and parameter namespace.
bool adaptAndPlan(const PlannerFn &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res) const override
Adapt the planning request if needed, call the planner function planner and update the planning respo...
std::unique_ptr< default_plan_request_adapter_parameters::ParamListener > param_listener_
Concept in MoveIt which can be used to modify the planning problem and resulting trajectory (pre-proc...
std::function< bool(const planning_scene::PlanningSceneConstPtr &, const planning_interface::MotionPlanRequest &, planning_interface::MotionPlanResponse &)> PlannerFn
Functional interface to call a planning function.
bool computeTimeStamps(robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) const override
Compute a trajectory with waypoints spaced equally in time (according to resample_dt_)....
Main namespace for MoveIt.
rclcpp::Logger makeChildLogger(const std::string &name)
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
This namespace includes the central class for representing planning contexts.
CLASS_LOADER_REGISTER_CLASS(stomp_moveit::StompSmoothingAdapter, planning_request_adapter::PlanningRequestAdapter)
Response to a planning query.
robot_trajectory::RobotTrajectoryPtr trajectory