37 #include <eigen3/Eigen/Eigen>
38 #include <kdl/path.hpp>
39 #include <kdl/velocityprofile.hpp>
50 moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
56 moveit_msgs::msg::MoveItErrorCodes::INVALID_LINK_NAME);
58 moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
83 const std::string& group_name);
88 void extractMotionPlanInfo(
const planning_scene::PlanningSceneConstPtr&
scene,
93 trajectory_msgs::msg::JointTrajectory& joint_trajectory)
override;
108 std::unique_ptr<KDL::Path> setPathCIRC(
const MotionPlanInfo& info)
const;
This class combines CartesianLimit and JointLimits into on single class.
This class implements a trajectory generator of arcs in Cartesian space. The arc is specified by a st...
TrajectoryGeneratorCIRC(const moveit::core::RobotModelConstPtr &robot_model, const pilz_industrial_motion_planner::LimitsContainer &planner_limits, const std::string &group_name)
Constructor of CIRC 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