moveit2
The MoveIt Motion Planning Framework for ROS 2.
Namespaces | Classes | Typedefs | Functions
pilz_industrial_motion_planner Namespace Reference

Namespaces

 joint_limits_interface
 

Classes

class  CartesianLimit
 Set of cartesian limits, has values for velocity, acceleration and deceleration of both the translational and rotational part. More...
 
class  CartesianLimitsAggregator
 Obtains cartesian limits from the node parameters. More...
 
struct  CartesianTrajectory
 
struct  CartesianTrajectoryPoint
 
class  CommandListManager
 This class orchestrates the planning of single commands and command lists. More...
 
class  JointLimitsAggregator
 Unifies the joint limits from the given joint models with joint limits from the node parameters. More...
 
class  AggregationException
 A base class for all aggregation exceptions inheriting from std::runtime_exception. More...
 
class  AggregationBoundsViolationException
 
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  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 in the node parameters (loaded from yaml) More...
 
class  ValidationDifferentLimitsException
 Thrown when the limits differ. More...
 
class  ValidationBoundsViolationException
 Thrown when the limits from the param server are weaker than the ones obtained from the urdf. More...
 
class  LimitsContainer
 This class combines CartesianLimit and JointLimits into on single class. More...
 
class  MoveGroupSequenceAction
 Provide action to handle multiple trajectories and execute the result in the form of a MoveGroup capability (plugin). More...
 
class  MoveGroupSequenceService
 Provide service to blend multiple trajectories in the form of a MoveGroup capability (plugin). More...
 
class  PathCircleGenerator
 Generator class for KDL::Path_Circle from different circle representations. More...
 
class  CommandPlanner
 MoveIt Plugin for Planning with Standard 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 inheriting from PlanningContextLoader. More...
 
class  PlanComponentsBuilder
 Helper class to encapsulate the merge and blend process of trajectories. 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_industrial_motion_planner exceptions inheriting from std::runtime_exception. More...
 
class  ContextLoaderRegistrationException
 
struct  TrajectoryBlendRequest
 
struct  TrajectoryBlendResponse
 
class  TrajectoryBlender
 Base class of trajectory blenders. More...
 
class  TrajectoryBlenderTransitionWindow
 Trajectory blender implementing transition window algorithm. More...
 
class  MoveItErrorCodeException
 Exception storing an moveit_msgs::msg::MoveItErrorCodes value. More...
 
class  TemplatedMoveItErrorCodeException
 
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 VelocityProfileATrap. More...
 
class  VelocityProfileATrap
 A PTP Trajectory Generator of Asymmetric Trapezoidal Velocity Profile. Differences to VelocityProfile_Trap: More...
 
class  GetSolverTipFrameIntegrationTest
 
class  SolverMock
 
class  JointModelGroupMock
 
class  GetSolverTipFrameTest
 Test fixture for getSolverTipFrame tests. More...
 

Typedefs

using RobotTrajCont = std::vector< robot_trajectory::RobotTrajectoryPtr >
 
typedef joint_limits_interface::JointLimits JointLimit
 
typedef std::map< std::string, JointLimitJointLimitsMap
 
using MoveGroupSequenceGoalHandle = rclcpp_action::ServerGoalHandle< moveit_msgs::action::MoveGroupSequence >
 
using TipFrameFunc_t = std::function< const std::string &(const std::string &)>
 
typedef std::shared_ptr< PlanningContextLoaderPlanningContextLoaderPtr
 
typedef std::shared_ptr< const PlanningContextLoaderPlanningContextLoaderConstPtr
 
typedef std::shared_ptr< PlanningContextLoaderCIRCPlanningContextLoaderCIRCPtr
 
typedef std::shared_ptr< const PlanningContextLoaderCIRCPlanningContextLoaderCIRCConstPtr
 
typedef std::shared_ptr< PlanningContextLoaderLINPlanningContextLoaderLINPtr
 
typedef std::shared_ptr< const PlanningContextLoaderLINPlanningContextLoaderLINConstPtr
 
typedef std::shared_ptr< PlanningContextLoaderPTPPlanningContextLoaderPTPPtr
 
typedef std::shared_ptr< const PlanningContextLoaderPTPPlanningContextLoaderPTPConstPtr
 
typedef std::unique_ptr< TrajectoryBlenderTrajectoryBlenderUniquePtr
 

Functions

 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (NegativeBlendRadiusException, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (LastBlendRadiusNotZeroException, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (StartStateSetException, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (OverlappingBlendRadiiException, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (PlanningPipelineException, moveit_msgs::msg::MoveItErrorCodes::FAILURE)
 
 MOVEIT_CLASS_FORWARD (CommandPlanner)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (NoBlenderSetException, moveit_msgs::msg::MoveItErrorCodes::FAILURE)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (NoTipFrameFunctionSetException, moveit_msgs::msg::MoveItErrorCodes::FAILURE)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (NoRobotModelSetException, moveit_msgs::msg::MoveItErrorCodes::FAILURE)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (BlendingFailedException, moveit_msgs::msg::MoveItErrorCodes::FAILURE)
 
 MOVEIT_CLASS_FORWARD (PlanningContext)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (NoSolverException, moveit_msgs::msg::MoveItErrorCodes::FAILURE)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (MoreThanOneTipFrameException, moveit_msgs::msg::MoveItErrorCodes::FAILURE)
 
bool computePoseIK (const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name, const std::string &link_name, const Eigen::Isometry3d &pose, const std::string &frame_id, const std::map< std::string, double > &seed, std::map< std::string, double > &solution, bool check_self_collision=true, const double timeout=0.0)
 compute the inverse kinematics of a given pose, also check robot self collision More...
 
bool computePoseIK (const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name, const std::string &link_name, const geometry_msgs::msg::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, const double timeout=0.0)
 
bool computeLinkFK (const planning_scene::PlanningSceneConstPtr &scene, const std::string &link_name, const std::map< std::string, double > &joint_state, Eigen::Isometry3d &pose)
 compute the pose of a link at give robot state More...
 
bool computeLinkFK (const planning_scene::PlanningSceneConstPtr &scene, const std::string &link_name, const std::vector< std::string > &joint_names, const std::vector< double > &joint_positions, Eigen::Isometry3d &pose)
 
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...
 
bool generateJointTrajectory (const planning_scene::PlanningSceneConstPtr &scene, 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::msg::JointTrajectory &joint_trajectory, moveit_msgs::msg::MoveItErrorCodes &error_code, bool check_self_collision=false)
 Generate joint trajectory from a KDL Cartesian trajectory. More...
 
bool generateJointTrajectory (const planning_scene::PlanningSceneConstPtr &scene, const JointLimitsContainer &joint_limits, const pilz_industrial_motion_planner::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::msg::JointTrajectory &joint_trajectory, moveit_msgs::msg::MoveItErrorCodes &error_code, bool check_self_collision=false)
 Generate joint trajectory from a MultiDOFJointTrajectory. More...
 
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 isRobotStateEqual (const moveit::core::RobotState &state1, const moveit::core::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 moveit::core::RobotState &state, const std::string &group, double EPSILON)
 check if the robot state have zero velocity/acceleration 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...
 
bool intersectionFound (const Eigen::Vector3d &p_center, const Eigen::Vector3d &p_current, const Eigen::Vector3d &p_next, const double &r)
 
bool isStateColliding (const bool test_for_self_collision, const planning_scene::PlanningSceneConstPtr &scene, moveit::core::RobotState *state, const moveit::core::JointModelGroup *const group, const double *const ik_solution)
 Checks if current robot state is in self collision. More...
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (TrajectoryGeneratorInvalidLimitsException, moveit_msgs::msg::MoveItErrorCodes::FAILURE)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (VelocityScalingIncorrect, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (AccelerationScalingIncorrect, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (UnknownPlanningGroup, moveit_msgs::msg::MoveItErrorCodes::INVALID_GROUP_NAME)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (NoJointNamesInStartState, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (SizeMismatchInStartState, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (JointsOfStartStateOutOfRange, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (NonZeroVelocityInStartState, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (NotExactlyOneGoalConstraintGiven, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (OnlyOneGoalTypeAllowed, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (StartStateGoalStateMismatch, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (JointConstraintDoesNotBelongToGroup, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (JointsOfGoalOutOfRange, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (PositionConstraintNameMissing, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (OrientationConstraintNameMissing, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (PositionOrientationConstraintNameMismatch, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (NoIKSolverAvailable, moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (NoPrimitivePoseGiven, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (CircleNoPlane, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (CircleToSmall, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (CenterPointDifferentRadius, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (CircTrajectoryConversionFailure, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (UnknownPathConstraintName, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (NoPositionConstraints, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (NoPrimitivePose, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (UnknownLinkNameOfAuxiliaryPoint, moveit_msgs::msg::MoveItErrorCodes::INVALID_LINK_NAME)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (NumberOfConstraintsMismatch, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (CircJointMissingInStartState, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (CircInverseForGoalIncalculable, moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (LinTrajectoryConversionFailure, moveit_msgs::msg::MoveItErrorCodes::FAILURE)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (JointNumberMismatch, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (LinJointMissingInStartState, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (LinInverseForGoalIncalculable, moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (PtpVelocityProfileSyncFailed, moveit_msgs::msg::MoveItErrorCodes::FAILURE)
 
 CREATE_MOVEIT_ERROR_CODE_EXCEPTION (PtpNoIkSolutionForGoalPose, moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION)
 
std::ostream & operator<< (std::ostream &os, const VelocityProfileATrap &p)
 
 TEST_F (GetSolverTipFrameIntegrationTest, TestHasSolverManipulator)
 Check if hasSolver() can be called successfully for the manipulator group. More...
 
 TEST_F (GetSolverTipFrameIntegrationTest, TestHasSolverGripperGroup)
 Check if hasSolver() can be called successfully for the gripper group. More...
 
 TEST_F (GetSolverTipFrameIntegrationTest, TestGetTipSolverFrameManipulator)
 Check if getSolverTipFrame() can be called successfully for the manipulator group. More...
 
 TEST_F (GetSolverTipFrameIntegrationTest, TestGetTipSolverFrameGripper)
 Check if getSolverTipFrame() fails for gripper group. More...
 
 TEST_F (GetSolverTipFrameTest, TestExceptionErrorCodeMapping)
 Checks that each derived MoveItErrorCodeException contains the correct error code. More...
 
 TEST_F (GetSolverTipFrameTest, TestExceptionMoreThanOneTipFrame)
 Checks that an exceptions is thrown in case a group has more than one tip frame. More...
 
 TEST_F (GetSolverTipFrameTest, TestExceptionNoSolver)
 Checks that an exceptions is thrown in case a group does not possess a solver. More...
 
 TEST_F (GetSolverTipFrameTest, NullptrJointGroup)
 Checks that an exceptions is thrown in case a nullptr is specified as JointModelGroup. More...
 

Typedef Documentation

◆ JointLimit

Definition at line 65 of file joint_limits_extension.h.

◆ JointLimitsMap

Definition at line 66 of file joint_limits_extension.h.

◆ MoveGroupSequenceGoalHandle

using pilz_industrial_motion_planner::MoveGroupSequenceGoalHandle = typedef rclcpp_action::ServerGoalHandle<moveit_msgs::action::MoveGroupSequence>

Definition at line 47 of file move_group_sequence_action.h.

◆ PlanningContextLoaderCIRCConstPtr

Definition at line 66 of file planning_context_loader_circ.h.

◆ PlanningContextLoaderCIRCPtr

Definition at line 65 of file planning_context_loader_circ.h.

◆ PlanningContextLoaderConstPtr

Definition at line 118 of file planning_context_loader.h.

◆ PlanningContextLoaderLINConstPtr

Definition at line 66 of file planning_context_loader_lin.h.

◆ PlanningContextLoaderLINPtr

Definition at line 65 of file planning_context_loader_lin.h.

◆ PlanningContextLoaderPTPConstPtr

Definition at line 66 of file planning_context_loader_ptp.h.

◆ PlanningContextLoaderPTPPtr

Definition at line 65 of file planning_context_loader_ptp.h.

◆ PlanningContextLoaderPtr

Definition at line 117 of file planning_context_loader.h.

◆ RobotTrajCont

using pilz_industrial_motion_planner::RobotTrajCont = typedef std::vector<robot_trajectory::RobotTrajectoryPtr>

Definition at line 53 of file command_list_manager.h.

◆ TipFrameFunc_t

using pilz_industrial_motion_planner::TipFrameFunc_t = typedef std::function<const std::string&(const std::string&)>

Definition at line 51 of file plan_components_builder.h.

◆ TrajectoryBlenderUniquePtr

Definition at line 75 of file trajectory_blender.h.

Function Documentation

◆ computeLinkFK() [1/2]

bool pilz_industrial_motion_planner::computeLinkFK ( const planning_scene::PlanningSceneConstPtr &  scene,
const std::string &  link_name,
const std::map< std::string, double > &  joint_state,
Eigen::Isometry3d &  pose 
)

compute the pose of a link at give robot state

Parameters
robot_modelkinematic model of the robot
link_nametarget link name
joint_statejoint positions of this group
posepose of the link in base frame of robot model
Returns
true if succeed

Definition at line 118 of file trajectory_functions.cpp.

Here is the caller graph for this function:

◆ computeLinkFK() [2/2]

bool pilz_industrial_motion_planner::computeLinkFK ( const planning_scene::PlanningSceneConstPtr &  scene,
const std::string &  link_name,
const std::vector< std::string > &  joint_names,
const std::vector< double > &  joint_positions,
Eigen::Isometry3d &  pose 
)

◆ computePoseIK() [1/2]

bool pilz_industrial_motion_planner::computePoseIK ( const planning_scene::PlanningSceneConstPtr &  scene,
const std::string &  group_name,
const std::string &  link_name,
const Eigen::Isometry3d &  pose,
const std::string &  frame_id,
const std::map< std::string, double > &  seed,
std::map< std::string, double > &  solution,
bool  check_self_collision = true,
const double  timeout = 0.0 
)

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

Parameters
sceneplanning scene
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
timeouttimeout for IK, if not set the default solver timeout is used
Returns
true if succeed

Definition at line 48 of file trajectory_functions.cpp.

Here is the caller graph for this function:

◆ computePoseIK() [2/2]

bool pilz_industrial_motion_planner::computePoseIK ( const planning_scene::PlanningSceneConstPtr &  scene,
const std::string &  group_name,
const std::string &  link_name,
const geometry_msgs::msg::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,
const double  timeout = 0.0 
)

Definition at line 105 of file trajectory_functions.cpp.

Here is the call graph for this function:

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [1/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( AccelerationScalingIncorrect  ,
moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [2/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( BlendingFailedException  ,
moveit_msgs::msg::MoveItErrorCodes::FAILURE   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [3/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( CenterPointDifferentRadius  ,
moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [4/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( CircInverseForGoalIncalculable  ,
moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [5/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( CircJointMissingInStartState  ,
moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [6/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( CircleNoPlane  ,
moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [7/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( CircleToSmall  ,
moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [8/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( CircTrajectoryConversionFailure  ,
moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [9/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( JointConstraintDoesNotBelongToGroup  ,
moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [10/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( JointNumberMismatch  ,
moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [11/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( JointsOfGoalOutOfRange  ,
moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [12/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( JointsOfStartStateOutOfRange  ,
moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [13/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( LastBlendRadiusNotZeroException  ,
moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [14/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( LinInverseForGoalIncalculable  ,
moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [15/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( LinJointMissingInStartState  ,
moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [16/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( LinTrajectoryConversionFailure  ,
moveit_msgs::msg::MoveItErrorCodes::FAILURE   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [17/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( MoreThanOneTipFrameException  ,
moveit_msgs::msg::MoveItErrorCodes::FAILURE   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [18/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( NegativeBlendRadiusException  ,
moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [19/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( NoBlenderSetException  ,
moveit_msgs::msg::MoveItErrorCodes::FAILURE   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [20/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( NoIKSolverAvailable  ,
moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [21/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( NoJointNamesInStartState  ,
moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [22/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( NonZeroVelocityInStartState  ,
moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [23/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( NoPositionConstraints  ,
moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [24/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( NoPrimitivePose  ,
moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [25/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( NoPrimitivePoseGiven  ,
moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [26/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( NoRobotModelSetException  ,
moveit_msgs::msg::MoveItErrorCodes::FAILURE   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [27/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( NoSolverException  ,
moveit_msgs::msg::MoveItErrorCodes::FAILURE   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [28/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( NotExactlyOneGoalConstraintGiven  ,
moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [29/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( NoTipFrameFunctionSetException  ,
moveit_msgs::msg::MoveItErrorCodes::FAILURE   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [30/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( NumberOfConstraintsMismatch  ,
moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [31/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( OnlyOneGoalTypeAllowed  ,
moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [32/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( OrientationConstraintNameMissing  ,
moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [33/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( OverlappingBlendRadiiException  ,
moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [34/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( PlanningPipelineException  ,
moveit_msgs::msg::MoveItErrorCodes::FAILURE   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [35/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( PositionConstraintNameMissing  ,
moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [36/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( PositionOrientationConstraintNameMismatch  ,
moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [37/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( PtpNoIkSolutionForGoalPose  ,
moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [38/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( PtpVelocityProfileSyncFailed  ,
moveit_msgs::msg::MoveItErrorCodes::FAILURE   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [39/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( SizeMismatchInStartState  ,
moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [40/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( StartStateGoalStateMismatch  ,
moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [41/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( StartStateSetException  ,
moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [42/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( TrajectoryGeneratorInvalidLimitsException  ,
moveit_msgs::msg::MoveItErrorCodes::FAILURE   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [43/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( UnknownLinkNameOfAuxiliaryPoint  ,
moveit_msgs::msg::MoveItErrorCodes::INVALID_LINK_NAME   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [44/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( UnknownPathConstraintName  ,
moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [45/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( UnknownPlanningGroup  ,
moveit_msgs::msg::MoveItErrorCodes::INVALID_GROUP_NAME   
)

◆ CREATE_MOVEIT_ERROR_CODE_EXCEPTION() [46/46]

pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION ( VelocityScalingIncorrect  ,
moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN   
)

◆ determineAndCheckSamplingTime()

bool pilz_industrial_motion_planner::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 416 of file trajectory_functions.cpp.

Here is the caller graph for this function:

◆ generateJointTrajectory() [1/2]

bool pilz_industrial_motion_planner::generateJointTrajectory ( const planning_scene::PlanningSceneConstPtr &  scene,
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::msg::JointTrajectory &  joint_trajectory,
moveit_msgs::msg::MoveItErrorCodes &  error_code,
bool  check_self_collision = false 
)

Generate joint trajectory from a KDL Cartesian trajectory.

Parameters
sceneplanning scene
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

Definition at line 202 of file trajectory_functions.cpp.

Here is the caller graph for this function:

◆ generateJointTrajectory() [2/2]

bool pilz_industrial_motion_planner::generateJointTrajectory ( const planning_scene::PlanningSceneConstPtr &  scene,
const JointLimitsContainer joint_limits,
const pilz_industrial_motion_planner::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::msg::JointTrajectory &  joint_trajectory,
moveit_msgs::msg::MoveItErrorCodes &  error_code,
bool  check_self_collision = false 
)

Generate joint trajectory from a MultiDOFJointTrajectory.

Parameters
sceneplanning scene
trajectoryCartesian trajectory
infomotion plan information
sampling_time
joint_trajectory
error_code
Returns
true if succeed

Definition at line 319 of file trajectory_functions.cpp.

◆ intersectionFound()

bool pilz_industrial_motion_planner::intersectionFound ( const Eigen::Vector3d &  p_center,
const Eigen::Vector3d &  p_current,
const Eigen::Vector3d &  p_next,
const double &  r 
)

Definition at line 567 of file trajectory_functions.cpp.

◆ isRobotStateEqual()

bool pilz_industrial_motion_planner::isRobotStateEqual ( const moveit::core::RobotState state1,
const moveit::core::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.

Definition at line 467 of file trajectory_functions.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ isRobotStateStationary()

bool pilz_industrial_motion_planner::isRobotStateStationary ( const moveit::core::RobotState state,
const std::string &  group,
double  EPSILON 
)

check if the robot state have zero velocity/acceleration

Parameters
state
group
EPSILON
Returns

Definition at line 510 of file trajectory_functions.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ isStateColliding()

bool pilz_industrial_motion_planner::isStateColliding ( const bool  test_for_self_collision,
const planning_scene::PlanningSceneConstPtr &  scene,
moveit::core::RobotState state,
const moveit::core::JointModelGroup *const  group,
const double *const  ik_solution 
)

Checks if current robot state is in self collision.

Parameters
sceneplanning scene.
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 574 of file trajectory_functions.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ linearSearchIntersectionPoint()

bool pilz_industrial_motion_planner::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 529 of file trajectory_functions.cpp.

◆ MOVEIT_CLASS_FORWARD() [1/2]

pilz_industrial_motion_planner::MOVEIT_CLASS_FORWARD ( CommandPlanner  )

◆ MOVEIT_CLASS_FORWARD() [2/2]

pilz_industrial_motion_planner::MOVEIT_CLASS_FORWARD ( PlanningContext  )

◆ operator<<()

std::ostream & pilz_industrial_motion_planner::operator<< ( std::ostream &  os,
const VelocityProfileATrap p 
)

Definition at line 397 of file velocity_profile_atrap.cpp.

◆ TEST_F() [1/8]

pilz_industrial_motion_planner::TEST_F ( GetSolverTipFrameIntegrationTest  ,
TestGetTipSolverFrameGripper   
)

Check if getSolverTipFrame() fails for gripper group.

Definition at line 101 of file integrationtest_get_solver_tip_frame.cpp.

◆ TEST_F() [2/8]

pilz_industrial_motion_planner::TEST_F ( GetSolverTipFrameIntegrationTest  ,
TestGetTipSolverFrameManipulator   
)

Check if getSolverTipFrame() can be called successfully for the manipulator group.

Definition at line 93 of file integrationtest_get_solver_tip_frame.cpp.

◆ TEST_F() [3/8]

pilz_industrial_motion_planner::TEST_F ( GetSolverTipFrameIntegrationTest  ,
TestHasSolverGripperGroup   
)

Check if hasSolver() can be called successfully for the gripper group.

Definition at line 84 of file integrationtest_get_solver_tip_frame.cpp.

◆ TEST_F() [4/8]

pilz_industrial_motion_planner::TEST_F ( GetSolverTipFrameIntegrationTest  ,
TestHasSolverManipulator   
)

Check if hasSolver() can be called successfully for the manipulator group.

Definition at line 76 of file integrationtest_get_solver_tip_frame.cpp.

◆ TEST_F() [5/8]

pilz_industrial_motion_planner::TEST_F ( GetSolverTipFrameTest  ,
NullptrJointGroup   
)

Checks that an exceptions is thrown in case a nullptr is specified as JointModelGroup.

Definition at line 132 of file unittest_get_solver_tip_frame.cpp.

◆ TEST_F() [6/8]

pilz_industrial_motion_planner::TEST_F ( GetSolverTipFrameTest  ,
TestExceptionErrorCodeMapping   
)

Checks that each derived MoveItErrorCodeException contains the correct error code.

Definition at line 89 of file unittest_get_solver_tip_frame.cpp.

◆ TEST_F() [7/8]

pilz_industrial_motion_planner::TEST_F ( GetSolverTipFrameTest  ,
TestExceptionMoreThanOneTipFrame   
)

Checks that an exceptions is thrown in case a group has more than one tip frame.

Definition at line 106 of file unittest_get_solver_tip_frame.cpp.

◆ TEST_F() [8/8]

pilz_industrial_motion_planner::TEST_F ( GetSolverTipFrameTest  ,
TestExceptionNoSolver   
)

Checks that an exceptions is thrown in case a group does not possess a solver.

Definition at line 121 of file unittest_get_solver_tip_frame.cpp.

◆ verifySampleJointLimits()

bool pilz_industrial_motion_planner::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 141 of file trajectory_functions.cpp.

Here is the caller graph for this function: