This class orchestrates the planning of single commands and command lists.
More...
#include <command_list_manager.h>
|
| 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...
|
|
This class orchestrates the planning of single commands and command lists.
Definition at line 49 of file command_list_manager.h.
pilz_trajectory_generation::CommandListManager::CommandListManager |
( |
const ros::NodeHandle & |
nh, |
|
|
const robot_model::RobotModelConstPtr & |
model |
|
) |
| |
void pilz_trajectory_generation::CommandListManager::checkForNegativeRadii |
( |
const pilz_msgs::MotionSequenceRequest & |
req_list | ) |
|
|
staticprivate |
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_responses | Container of calculated/generated trajectories. |
radii | Container 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 |
- 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.
- 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.
- 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 |
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_scene | The planning scene to be used for trajectory generation. |
req_list | List 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
-
- Returns
- Container of generated trajectories.
Definition at line 205 of file command_list_manager.cpp.
moveit::core::RobotModelConstPtr pilz_trajectory_generation::CommandListManager::model_ |
|
private |
The documentation for this class was generated from the following files: