moveit2
The MoveIt Motion Planning Framework for ROS 2.
Classes | Namespaces | Functions
trajectory_generator.h File Reference
#include <sstream>
#include <string>
#include <Eigen/Geometry>
#include <kdl/frames.hpp>
#include <kdl/trajectory.hpp>
#include <moveit/planning_interface/planning_interface.h>
#include <moveit/robot_model/robot_model.h>
#include <moveit/planning_scene/planning_scene.h>
#include <pilz_industrial_motion_planner/joint_limits_extension.h>
#include <pilz_industrial_motion_planner/limits_container.h>
#include <pilz_industrial_motion_planner/trajectory_functions.h>
#include <pilz_industrial_motion_planner/trajectory_generation_exceptions.h>
Include dependency graph for trajectory_generator.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  pilz_industrial_motion_planner::TrajectoryGenerator
 Base class of trajectory generators. More...
 
class  pilz_industrial_motion_planner::TrajectoryGenerator::MotionPlanInfo
 This class is used to extract needed information from motion plan request. More...
 

Namespaces

 pilz_industrial_motion_planner
 

Functions

 pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION (TrajectoryGeneratorInvalidLimitsException, moveit_msgs::msg::MoveItErrorCodes::FAILURE)
 
 pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION (VelocityScalingIncorrect, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN)
 
 pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION (AccelerationScalingIncorrect, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN)
 
 pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION (UnknownPlanningGroup, moveit_msgs::msg::MoveItErrorCodes::INVALID_GROUP_NAME)
 
 pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION (NoJointNamesInStartState, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE)
 
 pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION (SizeMismatchInStartState, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE)
 
 pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION (JointsOfStartStateOutOfRange, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE)
 
 pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION (NonZeroVelocityInStartState, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE)
 
 pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION (NotExactlyOneGoalConstraintGiven, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS)
 
 pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION (OnlyOneGoalTypeAllowed, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS)
 
 pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION (StartStateGoalStateMismatch, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS)
 
 pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION (JointConstraintDoesNotBelongToGroup, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS)
 
 pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION (JointsOfGoalOutOfRange, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS)
 
 pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION (PositionConstraintNameMissing, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS)
 
 pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION (OrientationConstraintNameMissing, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS)
 
 pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION (PositionOrientationConstraintNameMismatch, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS)
 
 pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION (NoIKSolverAvailable, moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION)
 
 pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION (NoPrimitivePoseGiven, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS)