40 #include <Eigen/Geometry>
41 #include <kdl/frames.hpp>
42 #include <kdl/trajectory.hpp>
55 moveit_msgs::msg::MoveItErrorCodes::FAILURE);
59 moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
65 moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
69 moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
73 moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
75 moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
79 moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
81 moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
83 moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
142 const double& max_acceleration_scaling_factor,
143 const std::unique_ptr<KDL::Path>& path)
const;
157 virtual void extractMotionPlanInfo(
const planning_scene::PlanningSceneConstPtr&
scene,
160 virtual void plan(
const planning_scene::PlanningSceneConstPtr&
scene,
162 const double& sampling_time, trajectory_msgs::msg::JointTrajectory& joint_trajectory) = 0;
212 const trajectory_msgs::msg::JointTrajectory& joint_trajectory,
217 void checkForValidGroupName(
const std::string& group_name)
const;
230 void checkStartState(
const moveit_msgs::msg::RobotState& start_state,
const std::string&
group)
const;
232 void checkGoalConstraints(
const moveit_msgs::msg::MotionPlanRequest::_goal_constraints_type& goal_constraints,
235 void checkJointGoalConstraint(
const moveit_msgs::msg::Constraints& constraint,
const std::string& group_name)
const;
237 void checkCartesianGoalConstraint(
const moveit_msgs::msg::Constraints& constraint,
245 sensor_msgs::msg::JointState filterGroupValues(
const sensor_msgs::msg::JointState& robot_state,
246 const std::string&
group)
const;
251 static bool isScalingFactorValid(
const double& scaling_factor);
252 static void checkVelocityScaling(
const double& scaling_factor);
253 static void checkAccelerationScaling(
const double& scaling_factor);
259 static bool isCartesianGoalGiven(
const moveit_msgs::msg::Constraints& constraint);
264 static bool isJointGoalGiven(
const moveit_msgs::msg::Constraints& constraint);
270 static bool isOnlyOneGoalTypeGiven(
const moveit_msgs::msg::Constraints& constraint);
278 const std::unique_ptr<rclcpp::Clock>
clock_;
281 inline bool TrajectoryGenerator::isScalingFactorValid(
const double& scaling_factor)
286 inline bool TrajectoryGenerator::isCartesianGoalGiven(
const moveit_msgs::msg::Constraints& constraint)
288 return constraint.position_constraints.size() == 1 && constraint.orientation_constraints.size() == 1;
291 inline bool TrajectoryGenerator::isJointGoalGiven(
const moveit_msgs::msg::Constraints& constraint)
293 return !constraint.joint_constraints.empty();
296 inline bool TrajectoryGenerator::isOnlyOneGoalTypeGiven(
const moveit_msgs::msg::Constraints& constraint)
298 return (isJointGoalGiven(constraint) && !isCartesianGoalGiven(constraint)) ||
299 (!isJointGoalGiven(constraint) && isCartesianGoalGiven(constraint));
Representation of a robot's state. This includes position, velocity, acceleration and effort.
This class combines CartesianLimit and JointLimits into on single class.
This class is used to extract needed information from motion plan request.
std::pair< std::string, Eigen::Vector3d > circ_path_point
MotionPlanInfo(const planning_scene::PlanningSceneConstPtr &scene, const planning_interface::MotionPlanRequest &req)
std::map< std::string, double > goal_joint_position
planning_scene::PlanningSceneConstPtr start_scene
Eigen::Isometry3d start_pose
Eigen::Isometry3d goal_pose
std::map< std::string, double > start_joint_position
Base class of trajectory generators.
const moveit::core::RobotModelConstPtr robot_model_
static constexpr double VELOCITY_TOLERANCE
TrajectoryGenerator(const moveit::core::RobotModelConstPtr &robot_model, const pilz_industrial_motion_planner::LimitsContainer &planner_limits)
bool generate(const planning_scene::PlanningSceneConstPtr &scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res, double sampling_time=0.1)
generate robot trajectory with given sampling time
std::unique_ptr< KDL::VelocityProfile > cartesianTrapVelocityProfile(const double &max_velocity_scaling_factor, const double &max_acceleration_scaling_factor, const std::unique_ptr< KDL::Path > &path) const
build cartesian velocity profile for the path
static constexpr double MIN_SCALING_FACTOR
virtual ~TrajectoryGenerator()=default
const pilz_industrial_motion_planner::LimitsContainer planner_limits_
const std::unique_ptr< rclcpp::Clock > clock_
static constexpr double MAX_SCALING_FACTOR
CREATE_MOVEIT_ERROR_CODE_EXCEPTION(NegativeBlendRadiusException, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN)
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest