37 #include <eigen3/Eigen/Eigen>
38 #include <kdl/rotational_interpolation_sa.hpp>
69 const std::string& group_name);
72 void extractMotionPlanInfo(
const planning_scene::PlanningSceneConstPtr&
scene,
77 trajectory_msgs::msg::JointTrajectory& joint_trajectory)
override;
83 std::unique_ptr<KDL::Path> setPathLIN(
const Eigen::Affine3d& start_pose,
const Eigen::Affine3d& goal_pose)
const;
This class combines CartesianLimit and JointLimits into on single class.
This class implements a linear trajectory generator in Cartesian space. The Cartesian trajetory are b...
TrajectoryGeneratorLIN(const moveit::core::RobotModelConstPtr &robot_model, const pilz_industrial_motion_planner::LimitsContainer &planner_limits, const std::string &group_name)
Constructor of LIN 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