moveit2
The MoveIt Motion Planning Framework for ROS 2.
Classes | Namespaces | Typedefs | Functions
command_list_manager.h File Reference
#include <string>
#include <memory>
#include <functional>
#include <moveit/planning_interface/planning_interface.h>
#include <moveit/planning_pipeline/planning_pipeline.h>
#include <moveit_msgs/msg/motion_plan_response.hpp>
#include <moveit_msgs/msg/motion_sequence_request.hpp>
#include <pilz_industrial_motion_planner/plan_components_builder.h>
#include <pilz_industrial_motion_planner/trajectory_blender.h>
#include <pilz_industrial_motion_planner/trajectory_generation_exceptions.h>
#include <cartesian_limits_parameters.hpp>
Include dependency graph for command_list_manager.h:
This graph shows which files directly or indirectly include this file:

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

 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)