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

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

#include <plan_components_builder.h>

Public Member Functions

void append (const robot_trajectory::RobotTrajectoryPtr &other, const double blend_radius)
 Appends the specified trajectory to the trajectory container under construction. More...
 
std::vector< robot_trajectory::RobotTrajectoryPtr > build () const
 
void reset ()
 Clears the trajectory container under construction. More...
 
void setBlender (std::unique_ptr< pilz::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...
 

Private Member Functions

void blend (const robot_trajectory::RobotTrajectoryPtr &other, const double blend_radius)
 

Static Private Member Functions

static void appendWithStrictTimeIncrease (robot_trajectory::RobotTrajectory &result, const robot_trajectory::RobotTrajectory &source)
 Appends a trajectory to a result trajectory leaving out the first point, if it matches the last point of the result trajectory. More...
 

Private Attributes

std::unique_ptr< pilz::TrajectoryBlenderblender_
 Blender used to blend two trajectories. More...
 
moveit::core::RobotModelConstPtr model_
 Robot model needed to create new trajectory container elements. More...
 
std::vector< robot_trajectory::RobotTrajectoryPtr > traj_cont_
 The trajectory container under construction. More...
 
robot_trajectory::RobotTrajectoryPtr traj_tail_
 The previously added trajectory. More...
 

Static Private Attributes

static constexpr double ROBOT_STATE_EQUALITY_EPSILON = 1e-4
 Constant to check for equality of variables of two RobotState instances. More...
 

Detailed Description

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

Definition at line 47 of file plan_components_builder.h.

Member Function Documentation

void pilz_trajectory_generation::PlanComponentsBuilder::append ( 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
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 85 of file plan_components_builder.cpp.

void pilz_trajectory_generation::PlanComponentsBuilder::appendWithStrictTimeIncrease ( robot_trajectory::RobotTrajectory result,
const robot_trajectory::RobotTrajectory source 
)
staticprivate

Appends a trajectory to a result trajectory leaving out the first point, if it matches the last point of the result trajectory.

Note
Controllers, so far at least the ros_controllers::JointTrajectoryController require a timewise strictly increasing trajectory. If through appending the last point of the original trajectory gets repeated, it is removed here.

Definition at line 38 of file plan_components_builder.cpp.

void pilz_trajectory_generation::PlanComponentsBuilder::blend ( const robot_trajectory::RobotTrajectoryPtr &  other,
const double  blend_radius 
)
private

Definition at line 54 of file plan_components_builder.cpp.

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

Definition at line 27 of file plan_components_builder.cpp.

void pilz_trajectory_generation::PlanComponentsBuilder::reset ( void  )
inline

Clears the trajectory container under construction.

Definition at line 138 of file plan_components_builder.h.

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

Sets the blender used to blend two trajectories.

Definition at line 128 of file plan_components_builder.h.

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

Sets the robot model needed to create new trajectory elements.

Definition at line 133 of file plan_components_builder.h.

Member Data Documentation

std::unique_ptr<pilz::TrajectoryBlender> pilz_trajectory_generation::PlanComponentsBuilder::blender_
private

Blender used to blend two trajectories.

Definition at line 112 of file plan_components_builder.h.

moveit::core::RobotModelConstPtr pilz_trajectory_generation::PlanComponentsBuilder::model_
private

Robot model needed to create new trajectory container elements.

Definition at line 115 of file plan_components_builder.h.

constexpr double pilz_trajectory_generation::PlanComponentsBuilder::ROBOT_STATE_EQUALITY_EPSILON = 1e-4
staticprivate

Constant to check for equality of variables of two RobotState instances.

Definition at line 125 of file plan_components_builder.h.

std::vector<robot_trajectory::RobotTrajectoryPtr> pilz_trajectory_generation::PlanComponentsBuilder::traj_cont_
private

The trajectory container under construction.

Definition at line 121 of file plan_components_builder.h.

robot_trajectory::RobotTrajectoryPtr pilz_trajectory_generation::PlanComponentsBuilder::traj_tail_
private

The previously added trajectory.

Definition at line 118 of file plan_components_builder.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