Classes | Typedefs | Functions | Variables
pilz Namespace Reference

Classes

class  AggregationBoundsViolationException
 
class  AggregationException
 A base class for all aggregation exceptions inheriting from std::runtime_exception. More...
 
class  CartesianLimit
 Set os cartesian limits, has values for velocity, acceleration and deceleration of both the translational and rotational part. More...
 
class  CartesianLimitsAggregator
 Obtains cartesian limits from the parameter server. More...
 
struct  CartesianTrajectory
 
struct  CartesianTrajectoryPoint
 
class  CommandPlanner
 Moveit Plugin for Planning with Standart Robot Commands This planner is dedicated to return a instance of PlanningContext that corresponds to the requested motion command set as planner_id in the MotionPlanRequest). It can be easily extended with additional commands by creating a class inherting from PlanningContextLoader. More...
 
class  ContextLoaderRegistrationException
 
class  JointLimitsAggregator
 Unifies the joint limits from the given joint models with joint limits from the parameter server. More...
 
class  JointLimitsContainer
 Container for JointLimits, essentially a map with convenience functions. Adds the ability to as for limits and get a common limit that unifies all given limits. More...
 
class  JointLimitsValidator
 Validates the equality of all limits inside a container. More...
 
class  LimitsContainer
 This class combines CartesianLimit and JointLimits into on single class. More...
 
class  PathCircleGenerator
 Generator class for KDL::Path_Circle from different circle representations. More...
 
class  PlanningContextBase
 PlanningContext for obtaining trajectories. More...
 
class  PlanningContextCIRC
 PlanningContext for obtaining CIRC trajectories. More...
 
class  PlanningContextLIN
 PlanningContext for obtaining LIN trajectories. More...
 
class  PlanningContextLoader
 Base class for all PlanningContextLoaders. Since planning_interface::PlanningContext has a non empty ctor classes derived from it can not be plugins. This class serves as base class for wrappers. More...
 
class  PlanningContextLoaderCIRC
 Plugin that can generate instances of PlanningContextCIRC. Generates instances of PlanningContextLIN. More...
 
class  PlanningContextLoaderLIN
 Plugin that can generate instances of PlanningContextLIN. Generates instances of PlanningContextLIN. More...
 
class  PlanningContextLoaderPTP
 Plugin that can generate instances of PlanningContextPTP. Generates instances of PlanningContextPTP. More...
 
class  PlanningContextPTP
 PlanningContext for obtaining PTP trajectories. More...
 
class  PlanningException
 A base class for all pilz_planners exceptions inheriting from std::runtime_exception. More...
 
class  TrajectoryBlender
 Base class of trajectory blenders. More...
 
class  TrajectoryBlenderTransitionWindow
 Trajectory blender implementing transition window algorithm. More...
 
struct  TrajectoryBlendRequest
 
struct  TrajectoryBlendResponse
 
class  TrajectoryGenerator
 Base class of trajectory generators. More...
 
class  TrajectoryGeneratorCIRC
 This class implements a trajectory generator of arcs in Cartesian space. The arc is specified by a start pose, a goal pose and a interim point on the arc, or a point as the center of the circle which forms the arc. Complete circle is not covered by this generator. More...
 
class  TrajectoryGeneratorLIN
 This class implements a linear trajectory generator in Cartesian space. The Cartesian trajetory are based on trapezoid velocity profile. More...
 
class  TrajectoryGeneratorPTP
 This class implements a point-to-point trajectory generator based on VelocityProfile_ATrap. More...
 
class  ValidationBoundsViolationException
 Thrown when the limits from the param server are weaker than the ones obtained from the urdf. More...
 
class  ValidationDifferentLimitsException
 Thrown when the limits differ. More...
 
class  ValidationException
 A base class for all validations exceptions inheriting from std::runtime_exception. More...
 
class  ValidationJointMissingException
 Thrown the limits for a joint are defined in the urdf but not on the parameter server (loaded from yaml) More...
 
class  VelocityProfile_ATrap
 A PTP Trajectory Generator of Asymmetric Trapezoidal Velocity Profile. Differences to VelocityProfile_Trap: More...
 

Typedefs

typedef boost::shared_ptr< const PlanningContextLoaderCIRCPlanningContextLoaderCIRCConstPtr
 
typedef boost::shared_ptr< PlanningContextLoaderCIRCPlanningContextLoaderCIRCPtr
 
typedef boost::shared_ptr< const PlanningContextLoaderPlanningContextLoaderConstPtr
 
typedef boost::shared_ptr< const PlanningContextLoaderLINPlanningContextLoaderLINConstPtr
 
typedef boost::shared_ptr< PlanningContextLoaderLINPlanningContextLoaderLINPtr
 
typedef boost::shared_ptr< const PlanningContextLoaderPTPPlanningContextLoaderPTPConstPtr
 
typedef boost::shared_ptr< PlanningContextLoaderPTPPlanningContextLoaderPTPPtr
 
typedef boost::shared_ptr< PlanningContextLoaderPlanningContextLoaderPtr
 
typedef std::unique_ptr< TrajectoryBlenderTrajectoryBlenderUniquePtr
 

Functions

bool computeLinkFK (const robot_model::RobotModelConstPtr &robot_model, const std::string &link_name, const std::map< std::string, double > &joint_state, Eigen::Affine3d &pose)
 compute the pose of a link at give robot state More...
 
bool computeLinkFK (const robot_model::RobotModelConstPtr &robot_model, const std::string &link_name, const std::vector< std::string > &joint_names, const std::vector< double > &joint_positions, Eigen::Affine3d &pose)
 
bool computePoseIK (const robot_model::RobotModelConstPtr &robot_model, const std::string &group_name, const std::string &link_name, const Eigen::Affine3d &pose, const std::string &frame_id, const std::map< std::string, double > &seed, std::map< std::string, double > &solution, bool check_self_collision=true, int max_attempt=10, const double timeout=0.1)
 compute the inverse kinematics of a given pose, also check robot self collision More...
 
bool computePoseIK (const robot_model::RobotModelConstPtr &robot_model, const std::string &group_name, const std::string &link_name, const geometry_msgs::Pose &pose, const std::string &frame_id, const std::map< std::string, double > &seed, std::map< std::string, double > &solution, bool check_self_collision=true, int max_attempt=10, const double timeout=0.1)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (CircleNoPlane, moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (CircleToSmall, moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (PtpVelocityProfileSyncFailed, moveit_msgs::MoveItErrorCodes::FAILURE)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (CenterPointDifferentRadius, moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (LinTrajectoryConversionFailure, moveit_msgs::MoveItErrorCodes::FAILURE)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (PtpNoIkSolutionForGoalPose, moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (CircTrajectoryConversionFailure, moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (UnknownPathConstraintName, moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (JointNumberMismatch, moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (NoPositionConstraints, moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (LinJointMissingInStartState, moveit_msgs::MoveItErrorCodes::INVALID_ROBOT_STATE)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (LinInverseForGoalIncalculable, moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (NoPrimitivePose, moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (UnknownLinkNameOfAuxiliaryPoint, moveit_msgs::MoveItErrorCodes::INVALID_LINK_NAME)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (TrajectoryGeneratorInvalidLimitsException, moveit_msgs::MoveItErrorCodes::FAILURE)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (NumberOfConstraintsMismatch, moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (CircJointMissingInStartState, moveit_msgs::MoveItErrorCodes::INVALID_ROBOT_STATE)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (VelocityScalingIncorrect, moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (AccelerationScalingIncorrect, moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (CircInverseForGoalIncalculable, moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (UnknownPlanningGroup, moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (NoJointNamesInStartState, moveit_msgs::MoveItErrorCodes::INVALID_ROBOT_STATE)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (SizeMismatchInStartState, moveit_msgs::MoveItErrorCodes::INVALID_ROBOT_STATE)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (JointsOfStartStateOutOfRange, moveit_msgs::MoveItErrorCodes::INVALID_ROBOT_STATE)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (NonZeroVelocityInStartState, moveit_msgs::MoveItErrorCodes::INVALID_ROBOT_STATE)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (NotExactlyOneGoalConstraintGiven, moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (OnlyOneGoalTypeAllowed, moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (StartStateGoalStateMismatch, moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (JointConstraintDoesNotBelongToGroup, moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (JointsOfGoalOutOfRange, moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (PositionConstraintNameMissing, moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (OrientationConstraintNameMissing, moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (PositionOrientationConstraintNameMismatch, moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (NoIKSolverAvailable, moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (NoPrimitivePoseGiven, moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS)
 
bool determineAndCheckSamplingTime (const robot_trajectory::RobotTrajectoryPtr &first_trajectory, const robot_trajectory::RobotTrajectoryPtr &second_trajectory, double EPSILON, double &sampling_time)
 Determines the sampling time and checks that both trajectroies use the same sampling time. More...
 
bool generateJointTrajectory (const robot_model::RobotModelConstPtr &robot_model, const JointLimitsContainer &joint_limits, const KDL::Trajectory &trajectory, const std::string &group_name, const std::string &link_name, const std::map< std::string, double > &initial_joint_position, const double &sampling_time, trajectory_msgs::JointTrajectory &joint_trajectory, moveit_msgs::MoveItErrorCodes &error_code, bool check_self_collision=false)
 Generate joint trajectory from a KDL Cartesian trajectory. More...
 
bool generateJointTrajectory (const robot_model::RobotModelConstPtr &robot_model, const JointLimitsContainer &joint_limits, const pilz::CartesianTrajectory &trajectory, const std::string &group_name, const std::string &link_name, const std::map< std::string, double > &initial_joint_position, const std::map< std::string, double > &initial_joint_velocity, trajectory_msgs::JointTrajectory &joint_trajectory, moveit_msgs::MoveItErrorCodes &error_code, bool check_self_collision=false)
 Generate joint trajectory from a MultiDOFJointTrajectory. More...
 
bool intersectionFound (const Eigen::Vector3d &p_center, const Eigen::Vector3d &p_current, const Eigen::Vector3d &p_next, const double &r)
 
bool isRobotStateEqual (const robot_state::RobotState &state1, const robot_state::RobotState &state2, const std::string &joint_group_name, double epsilon)
 Check if the two robot states have the same joint position/velocity/acceleration. More...
 
bool isRobotStateStationary (const robot_state::RobotState &state, const std::string &group, double EPSILON)
 check if the robot state have zero velocity/acceleartion More...
 
bool isStateColliding (const bool test_for_self_collision, const moveit::core::RobotModelConstPtr &robot_model, robot_state::RobotState *state, const robot_state::JointModelGroup *const group, const double *const ik_solution)
 Checks if current robot state is in self collision. More...
 
bool linearSearchIntersectionPoint (const std::string &link_name, const Eigen::Vector3d &center_position, const double &r, const robot_trajectory::RobotTrajectoryPtr &traj, bool inverseOrder, std::size_t &index)
 Performs a linear search for the intersection point of the trajectory with the blending radius. More...
 
std::ostream & operator<< (std::ostream &os, const VelocityProfile_ATrap &p)
 
bool verifySampleJointLimits (const std::map< std::string, double > &position_last, const std::map< std::string, double > &velocity_last, const std::map< std::string, double > &position_current, double duration_last, double duration_current, const JointLimitsContainer &joint_limits)
 verify the velocity/acceleration limits of current sample (based on backward difference computation) v(k) = [x(k) - x(k-1)]/[t(k) - t(k-1)] a(k) = [v(k) - v(k-1)]/[t(k) - t(k-2)]*2 More...
 

Variables

static const std::string PARAM_NAMESPACE_LIMTS = "robot_description_planning"
 

Typedef Documentation

Definition at line 50 of file planning_context_loader_circ.h.

Definition at line 49 of file planning_context_loader_circ.h.

Definition at line 105 of file planning_context_loader.h.

Definition at line 50 of file planning_context_loader_lin.h.

Definition at line 49 of file planning_context_loader_lin.h.

Definition at line 50 of file planning_context_loader_ptp.h.

Definition at line 49 of file planning_context_loader_ptp.h.

Definition at line 104 of file planning_context_loader.h.

Definition at line 56 of file trajectory_blender.h.

Function Documentation

bool pilz::computeLinkFK ( const robot_model::RobotModelConstPtr &  robot_model,
const std::string &  link_name,
const std::map< std::string, double > &  joint_state,
Eigen::Affine3d &  pose 
)

compute the pose of a link at give robot state

Parameters
robot_modelkinematic model of the robot
link_nametarget link name
joint_statejoint positons of this group
posepose of the link in base frame of robot model
Returns
true if succeed
bool pilz::computeLinkFK ( const robot_model::RobotModelConstPtr &  robot_model,
const std::string &  link_name,
const std::vector< std::string > &  joint_names,
const std::vector< double > &  joint_positions,
Eigen::Affine3d &  pose 
)
bool pilz::computePoseIK ( const robot_model::RobotModelConstPtr &  robot_model,
const std::string &  group_name,
const std::string &  link_name,
const Eigen::Affine3d &  pose,
const std::string &  frame_id,
const std::map< std::string, double > &  seed,
std::map< std::string, double > &  solution,
bool  check_self_collision = true,
int  max_attempt = 10,
const double  timeout = 0.1 
)

compute the inverse kinematics of a given pose, also check robot self collision

Parameters
robot_modelkinematic model of the robot
group_namename of planning group
link_namename of target link
posetarget pose in IK solver Frame
frame_idreference frame of the target pose
seedseed state of IK solver
solutionsolution of IK
check_self_collisiontrue to enable self collision checking after IK computation
max_attemptmaximal attempts of IK
Returns
true if succeed
bool pilz::computePoseIK ( const robot_model::RobotModelConstPtr &  robot_model,
const std::string &  group_name,
const std::string &  link_name,
const geometry_msgs::Pose pose,
const std::string &  frame_id,
const std::map< std::string, double > &  seed,
std::map< std::string, double > &  solution,
bool  check_self_collision = true,
int  max_attempt = 10,
const double  timeout = 0.1 
)
pilz::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( CircleNoPlane  ,
moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN   
)
pilz::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( CircleToSmall  ,
moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN   
)
pilz::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( PtpVelocityProfileSyncFailed  ,
moveit_msgs::MoveItErrorCodes::FAILURE   
)
pilz::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( CenterPointDifferentRadius  ,
moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN   
)
pilz::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( LinTrajectoryConversionFailure  ,
moveit_msgs::MoveItErrorCodes::FAILURE   
)
pilz::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( PtpNoIkSolutionForGoalPose  ,
moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION   
)
pilz::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( CircTrajectoryConversionFailure  ,
moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN   
)
pilz::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( UnknownPathConstraintName  ,
moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN   
)
pilz::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( JointNumberMismatch  ,
moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS   
)
pilz::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( NoPositionConstraints  ,
moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN   
)
pilz::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( LinJointMissingInStartState  ,
moveit_msgs::MoveItErrorCodes::INVALID_ROBOT_STATE   
)
pilz::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( LinInverseForGoalIncalculable  ,
moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION   
)
pilz::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( NoPrimitivePose  ,
moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN   
)
pilz::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( UnknownLinkNameOfAuxiliaryPoint  ,
moveit_msgs::MoveItErrorCodes::INVALID_LINK_NAME   
)
pilz::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( TrajectoryGeneratorInvalidLimitsException  ,
moveit_msgs::MoveItErrorCodes::FAILURE   
)
pilz::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( NumberOfConstraintsMismatch  ,
moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS   
)
pilz::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( CircJointMissingInStartState  ,
moveit_msgs::MoveItErrorCodes::INVALID_ROBOT_STATE   
)
pilz::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( VelocityScalingIncorrect  ,
moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN   
)
pilz::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( AccelerationScalingIncorrect  ,
moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN   
)
pilz::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( CircInverseForGoalIncalculable  ,
moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION   
)
pilz::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( UnknownPlanningGroup  ,
moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME   
)
pilz::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( NoJointNamesInStartState  ,
moveit_msgs::MoveItErrorCodes::INVALID_ROBOT_STATE   
)
pilz::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( SizeMismatchInStartState  ,
moveit_msgs::MoveItErrorCodes::INVALID_ROBOT_STATE   
)
pilz::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( JointsOfStartStateOutOfRange  ,
moveit_msgs::MoveItErrorCodes::INVALID_ROBOT_STATE   
)
pilz::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( NonZeroVelocityInStartState  ,
moveit_msgs::MoveItErrorCodes::INVALID_ROBOT_STATE   
)
pilz::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( NotExactlyOneGoalConstraintGiven  ,
moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS   
)
pilz::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( OnlyOneGoalTypeAllowed  ,
moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS   
)
pilz::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( StartStateGoalStateMismatch  ,
moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS   
)
pilz::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( JointConstraintDoesNotBelongToGroup  ,
moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS   
)
pilz::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( JointsOfGoalOutOfRange  ,
moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS   
)
pilz::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( PositionConstraintNameMissing  ,
moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS   
)
pilz::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( OrientationConstraintNameMissing  ,
moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS   
)
pilz::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( PositionOrientationConstraintNameMismatch  ,
moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS   
)
pilz::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( NoIKSolverAvailable  ,
moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION   
)
pilz::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( NoPrimitivePoseGiven  ,
moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS   
)
bool pilz::determineAndCheckSamplingTime ( const robot_trajectory::RobotTrajectoryPtr &  first_trajectory,
const robot_trajectory::RobotTrajectoryPtr &  second_trajectory,
double  EPSILON,
double &  sampling_time 
)

Determines the sampling time and checks that both trajectroies use the same sampling time.

Returns
TRUE if the sampling time is equal between all given points (except the last two points of each trajectory), otherwise FALSE.

Definition at line 425 of file trajectory_functions.cpp.

bool pilz::generateJointTrajectory ( const robot_model::RobotModelConstPtr &  robot_model,
const JointLimitsContainer joint_limits,
const KDL::Trajectory trajectory,
const std::string &  group_name,
const std::string &  link_name,
const std::map< std::string, double > &  initial_joint_position,
const double &  sampling_time,
trajectory_msgs::JointTrajectory &  joint_trajectory,
moveit_msgs::MoveItErrorCodes &  error_code,
bool  check_self_collision = false 
)

Generate joint trajectory from a KDL Cartesian trajectory.

Parameters
robot_modelrobot kinematics model
joint_limitsjoint limits
trajectoryKDL Cartesian trajectory
group_namename of the planning group
link_namename of the target robot link
initial_joint_positioninitial joint positions, needed for selecting the ik solution
sampling_timesampling time of the generated trajectory
joint_trajectoryoutput as robot joint trajectory, first and last point will have zero velocity and acceleration
error_codedetailed error information
check_self_collisioncheck for self collision during creation
Returns
true if succeed
bool pilz::generateJointTrajectory ( const robot_model::RobotModelConstPtr &  robot_model,
const JointLimitsContainer joint_limits,
const pilz::CartesianTrajectory trajectory,
const std::string &  group_name,
const std::string &  link_name,
const std::map< std::string, double > &  initial_joint_position,
const std::map< std::string, double > &  initial_joint_velocity,
trajectory_msgs::JointTrajectory &  joint_trajectory,
moveit_msgs::MoveItErrorCodes &  error_code,
bool  check_self_collision = false 
)

Generate joint trajectory from a MultiDOFJointTrajectory.

Parameters
trajectoryCartesian trajectory
infomotion plan information
sampling_time
joint_trajectory
error_code
Returns
true if succeed
bool pilz::intersectionFound ( const Eigen::Vector3d &  p_center,
const Eigen::Vector3d &  p_current,
const Eigen::Vector3d &  p_next,
const double &  r 
)

Definition at line 582 of file trajectory_functions.cpp.

bool pilz::isRobotStateEqual ( const robot_state::RobotState &  state1,
const robot_state::RobotState &  state2,
const std::string &  joint_group_name,
double  epsilon 
)

Check if the two robot states have the same joint position/velocity/acceleration.

Parameters
joint_group_nameThe name of the joint group.
epsilonConstants defining how close the joint position/velocity/acceleration have to be to be recognized as equal.
Returns
True if joint positions, joint velocities and joint accelerations are equal, otherwise false.
bool pilz::isRobotStateStationary ( const robot_state::RobotState &  state,
const std::string &  group,
double  EPSILON 
)

check if the robot state have zero velocity/acceleartion

Parameters
state
group
EPSILON
Returns
bool pilz::isStateColliding ( const bool  test_for_self_collision,
const moveit::core::RobotModelConstPtr &  robot_model,
robot_state::RobotState *  state,
const robot_state::JointModelGroup *const  group,
const double *const  ik_solution 
)

Checks if current robot state is in self collision.

Parameters
test_for_self_collisionFlag to deactivate this check during IK.
robot_modelrobot kinematics model.
stateRobot state instance used for .
group
ik_solution
Returns

Definition at line 590 of file trajectory_functions.cpp.

bool pilz::linearSearchIntersectionPoint ( const std::string &  link_name,
const Eigen::Vector3d &  center_position,
const double &  r,
const robot_trajectory::RobotTrajectoryPtr &  traj,
bool  inverseOrder,
std::size_t &  index 
)

Performs a linear search for the intersection point of the trajectory with the blending radius.

Parameters
center_positionCenter of blending sphere.
rRadius of blending sphere.
trajThe trajectory.
inverseOrderTRUE: Farthest element from blending sphere center is located at the smallest index of trajectroy.
indexThe intersection index which has to be determined.

Definition at line 539 of file trajectory_functions.cpp.

std::ostream & pilz::operator<< ( std::ostream &  os,
const VelocityProfile_ATrap p 
)

Definition at line 369 of file velocity_profile_atrap.cpp.

bool pilz::verifySampleJointLimits ( const std::map< std::string, double > &  position_last,
const std::map< std::string, double > &  velocity_last,
const std::map< std::string, double > &  position_current,
double  duration_last,
double  duration_current,
const JointLimitsContainer joint_limits 
)

verify the velocity/acceleration limits of current sample (based on backward difference computation) v(k) = [x(k) - x(k-1)]/[t(k) - t(k-1)] a(k) = [v(k) - v(k-1)]/[t(k) - t(k-2)]*2

Parameters
position_lastposition of last sample
velocity_lastvelocity of last sample
position_currentposition of current sample
duration_lastduration of last sample
duration_currentduration of current sample
joint_limitsjoint limits
Returns

Definition at line 135 of file trajectory_functions.cpp.

Variable Documentation

const std::string pilz::PARAM_NAMESPACE_LIMTS = "robot_description_planning"
static

Definition at line 36 of file pilz_command_planner.cpp.



pilz_trajectory_generation
Author(s):
autogenerated on Mon Apr 6 2020 03:17:33