moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | List of all members
pilz_industrial_motion_planner::PlanComponentsBuilder Class Reference

Helper class to encapsulate the merge and blend process of trajectories. More...

#include <plan_components_builder.h>

Public Member Functions

void setBlender (std::unique_ptr< pilz_industrial_motion_planner::TrajectoryBlender > blender)
 Sets the blender used to blend two trajectories. More...
 
void setModel (const moveit::core::RobotModelConstPtr &model)
 Sets the robot model needed to create new trajectory elements. More...
 
void append (const planning_scene::PlanningSceneConstPtr &planning_scene, const robot_trajectory::RobotTrajectoryPtr &other, const double blend_radius)
 Appends the specified trajectory to the trajectory container under construction. More...
 
void reset ()
 Clears the trajectory container under construction. More...
 
std::vector< robot_trajectory::RobotTrajectoryPtr > build () const
 

Detailed Description

Helper class to encapsulate the merge and blend process of trajectories.

Definition at line 63 of file plan_components_builder.h.

Member Function Documentation

◆ append()

void pilz_industrial_motion_planner::PlanComponentsBuilder::append ( const planning_scene::PlanningSceneConstPtr &  planning_scene,
const robot_trajectory::RobotTrajectoryPtr &  other,
const double  blend_radius 
)

Appends the specified trajectory to the trajectory container under construction.

The appending complies to the following rules:

  • A trajectory is simply added/attached to the previous trajectory:
    • if they are from the same group and
    • if the specified blend_radius is zero.
  • A trajectory is blended together with the previous trajectory:
    • if they are from the same group and
    • if the specified blend_radius is GREATER than zero.
  • A new trajectory element is created and the given trajectory is appended/attached to the newly created empty trajectory:
    • if the given and previous trajectory are from different groups.
Parameters
planning_sceneThe scene planning is occurring in.
otherTrajectories which has to be added to the trajectory container under construction.
blend_radiusThe blending radius between the previous and the specified trajectory.

Definition at line 102 of file plan_components_builder.cpp.

Here is the caller graph for this function:

◆ build()

std::vector< robot_trajectory::RobotTrajectoryPtr > pilz_industrial_motion_planner::PlanComponentsBuilder::build ( ) const
Returns
The final trajectory container which results from the append calls.

Definition at line 43 of file plan_components_builder.cpp.

Here is the caller graph for this function:

◆ reset()

void pilz_industrial_motion_planner::PlanComponentsBuilder::reset ( )
inline

Clears the trajectory container under construction.

Definition at line 157 of file plan_components_builder.h.

Here is the caller graph for this function:

◆ setBlender()

void pilz_industrial_motion_planner::PlanComponentsBuilder::setBlender ( std::unique_ptr< pilz_industrial_motion_planner::TrajectoryBlender blender)
inline

Sets the blender used to blend two trajectories.

Definition at line 147 of file plan_components_builder.h.

Here is the caller graph for this function:

◆ setModel()

void pilz_industrial_motion_planner::PlanComponentsBuilder::setModel ( const moveit::core::RobotModelConstPtr &  model)
inline

Sets the robot model needed to create new trajectory elements.

Definition at line 152 of file plan_components_builder.h.

Here is the caller graph for this function:

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