#include <eigen3/Eigen/Eigen>
#include <kdl/path.hpp>
#include <kdl/velocityprofile.hpp>
#include <moveit/planning_scene/planning_scene.h>
#include <pilz_industrial_motion_planner/trajectory_generator.h>
Go to the source code of this file.
|
class | pilz_industrial_motion_planner::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...
|
|
|
| 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 (CenterPointDifferentRadius, 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 (UnknownPathConstraintName, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN) |
|
| 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 (UnknownLinkNameOfAuxiliaryPoint, moveit_msgs::msg::MoveItErrorCodes::INVALID_LINK_NAME) |
|
| 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 (CircInverseForGoalIncalculable, moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION) |
|