39 #include <eigen3/Eigen/Eigen>
65 const std::string& group_name);
68 void extractMotionPlanInfo(
const planning_scene::PlanningSceneConstPtr&
scene,
81 void planPTP(
const std::map<std::string, double>& start_pos,
const std::map<std::string, double>& goal_pos,
82 trajectory_msgs::msg::JointTrajectory& joint_trajectory,
const double& velocity_scaling_factor,
83 const double& acceleration_scaling_factor,
const double& sampling_time);
87 trajectory_msgs::msg::JointTrajectory& joint_trajectory)
override;
90 const double MIN_MOVEMENT = 0.001;
Container for JointLimits, essentially a map with convenience functions. Adds the ability to as for l...
This class combines CartesianLimit and JointLimits into on single class.
This class implements a point-to-point trajectory generator based on VelocityProfileATrap.
TrajectoryGeneratorPTP(const moveit::core::RobotModelConstPtr &robot_model, const pilz_industrial_motion_planner::LimitsContainer &planner_limits, const std::string &group_name)
Constructor of PTP Trajectory Generator.
This class is used to extract needed information from motion plan request.
Base class of trajectory generators.
CREATE_MOVEIT_ERROR_CODE_EXCEPTION(NegativeBlendRadiusException, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN)
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
Extends joint_limits_interface::JointLimits with a deceleration parameter.