Public Member Functions | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes | List of all members
pilz_trajectory_generation::CommandListManager Class Reference

This class orchestrates the planning of single commands and command lists. More...

#include <command_list_manager.h>

Public Member Functions

 CommandListManager (const ros::NodeHandle &nh, const robot_model::RobotModelConstPtr &model)
 
RobotTrajCont solve (const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_pipeline::PlanningPipelinePtr &planning_pipeline, const pilz_msgs::MotionSequenceRequest &req_list)
 Generates trajectories for the specified list of motion commands. More...
 

Private Types

using GroupNamesCont = std::vector< std::string >
 
using MotionResponseCont = std::vector< planning_interface::MotionPlanResponse >
 
using RadiiCont = std::vector< double >
 
using RobotState_OptRef = boost::optional< const robot_state::RobotState & >
 

Private Member Functions

void checkForOverlappingRadii (const MotionResponseCont &resp_cont, const RadiiCont &radii) const
 Validates that two consecutive blending radii do not overlap. More...
 
bool checkRadiiForOverlap (const robot_trajectory::RobotTrajectory &traj_A, const double radii_A, const robot_trajectory::RobotTrajectory &traj_B, const double radii_B) const
 
MotionResponseCont solveSequenceItems (const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_pipeline::PlanningPipelinePtr &planning_pipeline, const pilz_msgs::MotionSequenceRequest &req_list) const
 Solve each sequence item individually. More...
 

Static Private Member Functions

static void checkForNegativeRadii (const pilz_msgs::MotionSequenceRequest &req_list)
 Checks that all blend radii are greater or equal to zero. More...
 
static void checkLastBlendRadiusZero (const pilz_msgs::MotionSequenceRequest &req_list)
 Checks that last blend radius is zero. More...
 
static void checkStartStates (const pilz_msgs::MotionSequenceRequest &req_list)
 Checks that each group in the specified request list has only one start state. More...
 
static void checkStartStatesOfGroup (const pilz_msgs::MotionSequenceRequest &req_list, const std::string &group_name)
 Checks that only the first request of the specified group has a start state in the specified request list. More...
 
static RadiiCont extractBlendRadii (const moveit::core::RobotModel &model, const pilz_msgs::MotionSequenceRequest &req_list)
 
static GroupNamesCont getGroupNames (const pilz_msgs::MotionSequenceRequest &req_list)
 
static RobotState_OptRef getPreviousEndState (const MotionResponseCont &motion_plan_responses, const std::string &group_name)
 
static bool isInvalidBlendRadii (const moveit::core::RobotModel &model, const pilz_msgs::MotionSequenceItem &item_A, const pilz_msgs::MotionSequenceItem &item_B)
 
static void setStartState (const MotionResponseCont &motion_plan_responses, const std::string &group_name, moveit_msgs::RobotState &start_state)
 Set start state to end state of previous calculated trajectory from group. More...
 

Private Attributes

moveit::core::RobotModelConstPtr model_
 Robot model. More...
 
ros::NodeHandle nh_
 Node handle. More...
 
PlanComponentsBuilder plan_comp_builder_
 Builder to construct the container containing the final trajectories. More...
 

Detailed Description

This class orchestrates the planning of single commands and command lists.

Definition at line 49 of file command_list_manager.h.

Member Typedef Documentation

using pilz_trajectory_generation::CommandListManager::GroupNamesCont = std::vector<std::string>
private

Definition at line 92 of file command_list_manager.h.

Definition at line 89 of file command_list_manager.h.

using pilz_trajectory_generation::CommandListManager::RadiiCont = std::vector<double>
private

Definition at line 91 of file command_list_manager.h.

using pilz_trajectory_generation::CommandListManager::RobotState_OptRef = boost::optional<const robot_state::RobotState& >
private

Definition at line 90 of file command_list_manager.h.

Constructor & Destructor Documentation

pilz_trajectory_generation::CommandListManager::CommandListManager ( const ros::NodeHandle nh,
const robot_model::RobotModelConstPtr &  model 
)

Definition at line 39 of file command_list_manager.cpp.

Member Function Documentation

void pilz_trajectory_generation::CommandListManager::checkForNegativeRadii ( const pilz_msgs::MotionSequenceRequest &  req_list)
staticprivate

Checks that all blend radii are greater or equal to zero.

Definition at line 232 of file command_list_manager.cpp.

void pilz_trajectory_generation::CommandListManager::checkForOverlappingRadii ( const MotionResponseCont resp_cont,
const RadiiCont radii 
) const
private

Validates that two consecutive blending radii do not overlap.

Parameters
motion_plan_responsesContainer of calculated/generated trajectories.
radiiContainer stating the blend radii.

Definition at line 118 of file command_list_manager.cpp.

void pilz_trajectory_generation::CommandListManager::checkLastBlendRadiusZero ( const pilz_msgs::MotionSequenceRequest &  req_list)
inlinestaticprivate

Checks that last blend radius is zero.

Definition at line 204 of file command_list_manager.h.

bool pilz_trajectory_generation::CommandListManager::checkRadiiForOverlap ( const robot_trajectory::RobotTrajectory traj_A,
const double  radii_A,
const robot_trajectory::RobotTrajectory traj_B,
const double  radii_B 
) const
private
Returns
TRUE if the blending radii of specified trajectories overlap, otherwise FALSE. The functions returns FALSE if both trajectories are from different groups or if both trajectories are end-effector groups.

Definition at line 95 of file command_list_manager.cpp.

void pilz_trajectory_generation::CommandListManager::checkStartStates ( const pilz_msgs::MotionSequenceRequest &  req_list)
staticprivate

Checks that each group in the specified request list has only one start state.

Definition at line 271 of file command_list_manager.cpp.

void pilz_trajectory_generation::CommandListManager::checkStartStatesOfGroup ( const pilz_msgs::MotionSequenceRequest &  req_list,
const std::string &  group_name 
)
staticprivate

Checks that only the first request of the specified group has a start state in the specified request list.

Definition at line 241 of file command_list_manager.cpp.

CommandListManager::RadiiCont pilz_trajectory_generation::CommandListManager::extractBlendRadii ( const moveit::core::RobotModel model,
const pilz_msgs::MotionSequenceRequest &  req_list 
)
staticprivate
Returns
Container of radii extracted from the specified request list.

Please note: This functions sets invalid blend radii to zero. Invalid blend radii are:

  • blend radii between end-effectors and
  • blend raddi between different groups.

Definition at line 189 of file command_list_manager.cpp.

CommandListManager::GroupNamesCont pilz_trajectory_generation::CommandListManager::getGroupNames ( const pilz_msgs::MotionSequenceRequest &  req_list)
staticprivate
Returns
Returns all group names which are present in the specified request.

Definition at line 285 of file command_list_manager.cpp.

CommandListManager::RobotState_OptRef pilz_trajectory_generation::CommandListManager::getPreviousEndState ( const MotionResponseCont motion_plan_responses,
const std::string &  group_name 
)
staticprivate
Returns
The last RobotState of the specified group which can be found in the specified vector.

Definition at line 136 of file command_list_manager.cpp.

bool pilz_trajectory_generation::CommandListManager::isInvalidBlendRadii ( const moveit::core::RobotModel model,
const pilz_msgs::MotionSequenceItem &  item_A,
const pilz_msgs::MotionSequenceItem &  item_B 
)
staticprivate
Returns
True in case of an invalid blend radii between specified command A and B, otherwise False. Invalid blend radii are:
  • blend radii between end-effectors and
  • blend raddi between different groups.

Definition at line 160 of file command_list_manager.cpp.

void pilz_trajectory_generation::CommandListManager::setStartState ( const MotionResponseCont motion_plan_responses,
const std::string &  group_name,
moveit_msgs::RobotState &  start_state 
)
staticprivate

Set start state to end state of previous calculated trajectory from group.

Definition at line 149 of file command_list_manager.cpp.

RobotTrajCont pilz_trajectory_generation::CommandListManager::solve ( const planning_scene::PlanningSceneConstPtr &  planning_scene,
const planning_pipeline::PlanningPipelinePtr &  planning_pipeline,
const pilz_msgs::MotionSequenceRequest &  req_list 
)

Generates trajectories for the specified list of motion commands.

The folloing rules apply:

  • If two consecutive trajectories are from the same group, they are simply attached to each other, given that the blend_radius is zero.
  • If two consecutive trajectories are from the same group, they are blended together, given that the blend_radius is GREATER than zero.
  • If two consecutive trajectories are from different groups, then the second trajectory is added as new element to the result container. All following trajectories are then attached to the new trajectory element (until all requests are processed or until the next group change).
Parameters
planning_sceneThe planning scene to be used for trajectory generation.
req_listList of motion requests containing: PTP, LIN, CIRC and/or gripper commands. Please note: A request is only valid if:
  • All blending radii are non negative.
  • The blending radius of the last request is 0.
  • Only the first request of each group has a start state.
  • Non of the blending radii overlapp each other.

Please note: Starts states do not need to state the joints of all groups. It is sufficient if a start state states only the joints of the group which it belongs to. Starts states can even be incomplete. In this case default values are set for the unset joints.

Returns
Contains the calculated/generated trajectories.

Definition at line 61 of file command_list_manager.cpp.

CommandListManager::MotionResponseCont pilz_trajectory_generation::CommandListManager::solveSequenceItems ( const planning_scene::PlanningSceneConstPtr &  planning_scene,
const planning_pipeline::PlanningPipelinePtr &  planning_pipeline,
const pilz_msgs::MotionSequenceRequest &  req_list 
) const
private

Solve each sequence item individually.

Parameters
planning_sceneThe planning_scene to be used for trajectory generation.
req_listContainer of requests for calculation/generation.
Returns
Container of generated trajectories.

Definition at line 205 of file command_list_manager.cpp.

Member Data Documentation

moveit::core::RobotModelConstPtr pilz_trajectory_generation::CommandListManager::model_
private

Robot model.

Definition at line 197 of file command_list_manager.h.

ros::NodeHandle pilz_trajectory_generation::CommandListManager::nh_
private

Node handle.

Definition at line 194 of file command_list_manager.h.

PlanComponentsBuilder pilz_trajectory_generation::CommandListManager::plan_comp_builder_
private

Builder to construct the container containing the final trajectories.

Definition at line 201 of file command_list_manager.h.


The documentation for this class was generated from the following files:


pilz_trajectory_generation
Author(s):
autogenerated on Mon Apr 6 2020 03:17:34