39#include <class_loader/class_loader.hpp>
42#include <default_response_adapter_parameters.hpp>
56 void initialize(
const rclcpp::Node::SharedPtr& node,
const std::string& parameter_namespace)
override
58 param_listener_ = std::make_unique<default_response_adapter_parameters::ParamListener>(node, parameter_namespace);
63 return std::string(
"AddTimeOptimalParameterization");
66 void adapt(
const planning_scene::PlanningSceneConstPtr& ,
73 RCLCPP_ERROR(
logger_,
"Cannot apply response adapter '%s' because MotionPlanResponse does not contain a path.",
75 res.
error_code = moveit::core::MoveItErrorCode::INVALID_MOTION_PLAN;
83 res.
error_code = moveit::core::MoveItErrorCode::SUCCESS;
87 RCLCPP_ERROR(
logger_,
"Response adapter '%s' failed to generate a trajectory.",
getDescription().c_str());
88 res.
error_code = moveit::core::MoveItErrorCode::FAILURE;
93 std::unique_ptr<default_response_adapter_parameters::ParamListener>
param_listener_;
This adapter uses the time-optimal trajectory generation method.
void adapt(const planning_scene::PlanningSceneConstPtr &, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res) const override
Adapt the planning response.
AddTimeOptimalParameterization()
std::string getDescription() const override
Get a description of this adapter.
void initialize(const rclcpp::Node::SharedPtr &node, const std::string ¶meter_namespace) override
Initialize parameters using the passed Node and parameter namespace.
std::unique_ptr< default_response_adapter_parameters::ParamListener > param_listener_
Concept in MoveIt which can be used to modify the planning solution (post-processing) in a planning p...
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.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
CLASS_LOADER_REGISTER_CLASS(default_planning_request_adapters::ResolveConstraintFrames, planning_interface::PlanningRequestAdapter)
Response to a planning query.
moveit::core::MoveItErrorCode error_code
robot_trajectory::RobotTrajectoryPtr trajectory