|
moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <string>#include <memory>#include <functional>#include <moveit/planning_interface/planning_interface.hpp>#include <moveit/planning_pipeline/planning_pipeline.hpp>#include <moveit_msgs/msg/motion_plan_response.hpp>#include <moveit_msgs/msg/motion_sequence_request.hpp>#include <pilz_industrial_motion_planner/plan_components_builder.hpp>#include <pilz_industrial_motion_planner/trajectory_blender.hpp>#include <pilz_industrial_motion_planner/trajectory_generation_exceptions.hpp>#include <pilz_industrial_motion_planner/cartesian_limits_parameters.hpp>

Go to the source code of this file.
Classes | |
| class | pilz_industrial_motion_planner::CommandListManager |
| This class orchestrates the planning of single commands and command lists. More... | |
Namespaces | |
| namespace | pilz_industrial_motion_planner |
Typedefs | |
| using | pilz_industrial_motion_planner::RobotTrajCont = std::vector< robot_trajectory::RobotTrajectoryPtr > |
Functions | |
| 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 (LastBlendRadiusNotZeroException, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN) | |
| 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 (OverlappingBlendRadiiException, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN) | |
| pilz_industrial_motion_planner::CREATE_MOVEIT_ERROR_CODE_EXCEPTION (PlanningPipelineException, moveit_msgs::msg::MoveItErrorCodes::FAILURE) | |