|
moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
Namespaces | |
| namespace | joint_limits_interface |
Classes | |
| class | AggregationBoundsViolationException |
| class | AggregationException |
| A base class for all aggregation exceptions inheriting from std::runtime_exception. More... | |
| struct | CartesianTrajectory |
| struct | CartesianTrajectoryPoint |
| class | CommandListManager |
| This class orchestrates the planning of single commands and command lists. 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 | ContextLoaderRegistrationException |
| class | GetSolverTipFrameIntegrationTest |
| class | GetSolverTipFrameTest |
| Test fixture for getSolverTipFrame tests. More... | |
| class | JointLimitsAggregator |
| Unifies the joint limits from the given joint models with joint limits from the node parameters. 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 | JointModelGroupMock |
| 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 | MoveItErrorCodeException |
| Exception storing an moveit_msgs::msg::MoveItErrorCodes value. More... | |
| class | PathCircleGenerator |
| Generator class for KDL::Path_Circle from different circle representations. 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 | SolverMock |
| class | TemplatedMoveItErrorCodeException |
| 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 VelocityProfileATrap. 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 in the node parameters (loaded from yaml) More... | |
| class | VelocityProfileATrap |
| A PTP Trajectory Generator of Asymmetric Trapezoidal Velocity Profile. Differences to VelocityProfile_Trap: More... | |
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 | |
| 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 (moveit::core::RobotState &robot_state, const std::string &link_name, const std::map< std::string, double > &joint_state, Eigen::Isometry3d &pose) |
| compute the pose of a link at a given robot state | |
| bool | computeLinkFK (moveit::core::RobotState &robot_state, 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 | |
| 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, 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. | |
| 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. | |
| 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. | |
| 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. | |
| bool | isRobotStateStationary (const moveit::core::RobotState &state, const std::string &group, double EPSILON) |
| check if the robot state have zero velocity/acceleration | |
| bool | linearSearchIntersectionPoint (const std::string &link_name, const Eigen::Vector3d ¢er_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. | |
| bool | intersectionFound (const Eigen::Vector3d &p_center, const Eigen::Vector3d &p_current, const Eigen::Vector3d &p_next, double r) |
| bool | isStateColliding (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. | |
| 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 (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 (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. | |
| TEST_F (GetSolverTipFrameIntegrationTest, TestHasSolverGripperGroup) | |
| Check if hasSolver() can be called successfully for the gripper group. | |
| TEST_F (GetSolverTipFrameIntegrationTest, TestGetTipSolverFrameManipulator) | |
| Check if getSolverTipFrame() can be called successfully for the manipulator group. | |
| TEST_F (GetSolverTipFrameIntegrationTest, TestGetTipSolverFrameGripper) | |
| Check if getSolverTipFrame() fails for gripper group. | |
| TEST_F (GetSolverTipFrameTest, TestExceptionErrorCodeMapping) | |
| Checks that each derived MoveItErrorCodeException contains the correct error code. | |
| TEST_F (GetSolverTipFrameTest, TestExceptionMoreThanOneTipFrame) | |
| Checks that an exceptions is thrown in case a group has more than one tip frame. | |
| TEST_F (GetSolverTipFrameTest, TestExceptionNoSolver) | |
| Checks that an exceptions is thrown in case a group does not possess a solver. | |
| TEST_F (GetSolverTipFrameTest, NullptrJointGroup) | |
| Checks that an exceptions is thrown in case a nullptr is specified as JointModelGroup. | |
Definition at line 65 of file joint_limits_extension.hpp.
| typedef std::map<std::string, JointLimit> pilz_industrial_motion_planner::JointLimitsMap |
Definition at line 66 of file joint_limits_extension.hpp.
| using pilz_industrial_motion_planner::MoveGroupSequenceGoalHandle = typedef rclcpp_action::ServerGoalHandle<moveit_msgs::action::MoveGroupSequence> |
Definition at line 47 of file move_group_sequence_action.hpp.
| typedef std::shared_ptr<const PlanningContextLoaderCIRC> pilz_industrial_motion_planner::PlanningContextLoaderCIRCConstPtr |
Definition at line 66 of file planning_context_loader_circ.hpp.
| typedef std::shared_ptr<PlanningContextLoaderCIRC> pilz_industrial_motion_planner::PlanningContextLoaderCIRCPtr |
Definition at line 65 of file planning_context_loader_circ.hpp.
| typedef std::shared_ptr<const PlanningContextLoader> pilz_industrial_motion_planner::PlanningContextLoaderConstPtr |
Definition at line 118 of file planning_context_loader.hpp.
| typedef std::shared_ptr<const PlanningContextLoaderLIN> pilz_industrial_motion_planner::PlanningContextLoaderLINConstPtr |
Definition at line 66 of file planning_context_loader_lin.hpp.
| typedef std::shared_ptr<PlanningContextLoaderLIN> pilz_industrial_motion_planner::PlanningContextLoaderLINPtr |
Definition at line 65 of file planning_context_loader_lin.hpp.
| typedef std::shared_ptr<const PlanningContextLoaderPTP> pilz_industrial_motion_planner::PlanningContextLoaderPTPConstPtr |
Definition at line 66 of file planning_context_loader_ptp.hpp.
| typedef std::shared_ptr<PlanningContextLoaderPTP> pilz_industrial_motion_planner::PlanningContextLoaderPTPPtr |
Definition at line 65 of file planning_context_loader_ptp.hpp.
| typedef std::shared_ptr<PlanningContextLoader> pilz_industrial_motion_planner::PlanningContextLoaderPtr |
Definition at line 117 of file planning_context_loader.hpp.
| using pilz_industrial_motion_planner::RobotTrajCont = typedef std::vector<robot_trajectory::RobotTrajectoryPtr> |
Definition at line 55 of file command_list_manager.hpp.
| 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.hpp.
| typedef std::unique_ptr<TrajectoryBlender> pilz_industrial_motion_planner::TrajectoryBlenderUniquePtr |
Definition at line 75 of file trajectory_blender.hpp.
| bool pilz_industrial_motion_planner::computeLinkFK | ( | moveit::core::RobotState & | robot_state, |
| const std::string & | link_name, | ||
| const std::map< std::string, double > & | joint_state, | ||
| Eigen::Isometry3d & | pose | ||
| ) |
compute the pose of a link at a given robot state
| robot_state | an arbitrary robot state (with collision objects attached) |
| link_name | target link name |
| joint_state | joint positions of this group |
| pose | pose of the link in base frame of robot model |
Definition at line 125 of file trajectory_functions.cpp.


| bool pilz_industrial_motion_planner::computeLinkFK | ( | moveit::core::RobotState & | robot_state, |
| const std::string & | link_name, | ||
| const std::vector< std::string > & | joint_names, | ||
| const std::vector< double > & | joint_positions, | ||
| Eigen::Isometry3d & | pose | ||
| ) |
| 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
| scene | planning scene |
| group_name | name of planning group |
| link_name | name of target link |
| pose | target pose in IK solver Frame |
| frame_id | reference frame of the target pose |
| seed | seed state of IK solver |
| solution | solution of IK |
| check_self_collision | true to enable self collision checking after IK computation |
| timeout | timeout for IK, if not set the default solver timeout is used |
Definition at line 57 of file trajectory_functions.cpp.


| 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 |
||
| ) |
| 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 | ( | BlendingFailedException | , |
| moveit_msgs::msg::MoveItErrorCodes::FAILURE | |||
| ) |
| pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION | ( | CenterPointDifferentRadius | , |
| moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN | |||
| ) |
| pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION | ( | CircInverseForGoalIncalculable | , |
| moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION | |||
| ) |
| pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION | ( | CircleNoPlane | , |
| moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN | |||
| ) |
| pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION | ( | CircleToSmall | , |
| moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN | |||
| ) |
| pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION | ( | CircTrajectoryConversionFailure | , |
| moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN | |||
| ) |
| 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 | ( | JointNumberMismatch | , |
| 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 | ( | JointsOfStartStateOutOfRange | , |
| moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE | |||
| ) |
| pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION | ( | LastBlendRadiusNotZeroException | , |
| moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN | |||
| ) |
| pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION | ( | LinInverseForGoalIncalculable | , |
| moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION | |||
| ) |
| pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION | ( | LinTrajectoryConversionFailure | , |
| moveit_msgs::msg::MoveItErrorCodes::FAILURE | |||
| ) |
| pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION | ( | MoreThanOneTipFrameException | , |
| moveit_msgs::msg::MoveItErrorCodes::FAILURE | |||
| ) |
| pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION | ( | NegativeBlendRadiusException | , |
| moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN | |||
| ) |
| pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION | ( | NoBlenderSetException | , |
| moveit_msgs::msg::MoveItErrorCodes::FAILURE | |||
| ) |
| 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 | ( | NoJointNamesInStartState | , |
| 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 | ( | NoPositionConstraints | , |
| moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN | |||
| ) |
| pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION | ( | NoPrimitivePose | , |
| moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN | |||
| ) |
| pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION | ( | NoPrimitivePoseGiven | , |
| moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS | |||
| ) |
| pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION | ( | NoRobotModelSetException | , |
| moveit_msgs::msg::MoveItErrorCodes::FAILURE | |||
| ) |
| pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION | ( | NoSolverException | , |
| moveit_msgs::msg::MoveItErrorCodes::FAILURE | |||
| ) |
| 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 | ( | NoTipFrameFunctionSetException | , |
| moveit_msgs::msg::MoveItErrorCodes::FAILURE | |||
| ) |
| pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION | ( | NumberOfConstraintsMismatch | , |
| 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 | ( | OrientationConstraintNameMissing | , |
| moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS | |||
| ) |
| pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION | ( | OverlappingBlendRadiiException | , |
| moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN | |||
| ) |
| pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION | ( | PlanningPipelineException | , |
| moveit_msgs::msg::MoveItErrorCodes::FAILURE | |||
| ) |
| 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 | ( | PositionOrientationConstraintNameMismatch | , |
| moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS | |||
| ) |
| pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION | ( | PtpNoIkSolutionForGoalPose | , |
| moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION | |||
| ) |
| pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION | ( | PtpVelocityProfileSyncFailed | , |
| moveit_msgs::msg::MoveItErrorCodes::FAILURE | |||
| ) |
| 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 | ( | StartStateGoalStateMismatch | , |
| moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS | |||
| ) |
| pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION | ( | StartStateSetException | , |
| moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE | |||
| ) |
| pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION | ( | TrajectoryGeneratorInvalidLimitsException | , |
| moveit_msgs::msg::MoveItErrorCodes::FAILURE | |||
| ) |
| pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION | ( | UnknownLinkNameOfAuxiliaryPoint | , |
| moveit_msgs::msg::MoveItErrorCodes::INVALID_LINK_NAME | |||
| ) |
| pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION | ( | UnknownPathConstraintName | , |
| 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 | ( | VelocityScalingIncorrect | , |
| moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN | |||
| ) |
| 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.
Definition at line 419 of file trajectory_functions.cpp.

| 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, | ||
| 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.
| scene | planning scene |
| joint_limits | joint limits |
| trajectory | KDL Cartesian trajectory |
| group_name | name of the planning group |
| link_name | name of the target robot link |
| initial_joint_position | initial joint positions, needed for selecting the ik solution |
| sampling_time | sampling time of the generated trajectory |
| joint_trajectory | output as robot joint trajectory, first and last point will have zero velocity and acceleration |
| error_code | detailed error information |
| check_self_collision | check for self collision during creation |
Definition at line 205 of file trajectory_functions.cpp.


| 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.
| scene | planning scene |
| trajectory | Cartesian trajectory |
| info | motion plan information |
| sampling_time | |
| joint_trajectory | |
| error_code |
Definition at line 322 of file trajectory_functions.cpp.

| bool pilz_industrial_motion_planner::intersectionFound | ( | const Eigen::Vector3d & | p_center, |
| const Eigen::Vector3d & | p_current, | ||
| const Eigen::Vector3d & | p_next, | ||
| double | r | ||
| ) |
Definition at line 569 of file trajectory_functions.cpp.

| 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.
| joint_group_name | The name of the joint group. |
| epsilon | Constants defining how close the joint position/velocity/acceleration have to be to be recognized as equal. |
Definition at line 470 of file trajectory_functions.cpp.


| 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
| state | |
| group | |
| EPSILON |
Definition at line 513 of file trajectory_functions.cpp.


| bool pilz_industrial_motion_planner::isStateColliding | ( | 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.
| scene | planning scene. |
| test_for_self_collision | Flag to deactivate this check during IK. |
| robot_model | robot kinematics model. |
| state | Robot state instance used for . |
| group | |
| ik_solution |
Definition at line 576 of file trajectory_functions.cpp.


| 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.
| center_position | Center of blending sphere. |
| r | Radius of blending sphere. |
| traj | The trajectory. |
| inverseOrder | TRUE: Farthest element from blending sphere center is located at the smallest index of trajectroy. |
| index | The intersection index which has to be determined. |
Definition at line 532 of file trajectory_functions.cpp.

| pilz_industrial_motion_planner::MOVEIT_CLASS_FORWARD | ( | CommandPlanner | ) |
| pilz_industrial_motion_planner::MOVEIT_CLASS_FORWARD | ( | PlanningContext | ) |
| std::ostream & pilz_industrial_motion_planner::operator<< | ( | std::ostream & | os, |
| const VelocityProfileATrap & | p | ||
| ) |
Definition at line 397 of file velocity_profile_atrap.cpp.
| 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.
| 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.
| 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.
| 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.
| 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.
| 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.
| 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.
| 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.
| 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
| position_last | position of last sample |
| velocity_last | velocity of last sample |
| position_current | position of current sample |
| duration_last | duration of last sample |
| duration_current | duration of current sample |
| joint_limits | joint limits |
Definition at line 145 of file trajectory_functions.cpp.
