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

Trajectory blender implementing transition window algorithm. More...

#include <trajectory_blender_transition_window.h>

Inheritance diagram for pilz_industrial_motion_planner::TrajectoryBlenderTransitionWindow:
Inheritance graph
[legend]
Collaboration diagram for pilz_industrial_motion_planner::TrajectoryBlenderTransitionWindow:
Collaboration graph
[legend]

Public Member Functions

 TrajectoryBlenderTransitionWindow (const LimitsContainer &planner_limits)
 
 ~TrajectoryBlenderTransitionWindow () override
 
bool blend (const planning_scene::PlanningSceneConstPtr &planning_scene, const pilz_industrial_motion_planner::TrajectoryBlendRequest &req, pilz_industrial_motion_planner::TrajectoryBlendResponse &res) override
 Blend two trajectories using transition window. The trajectories have to be equally and uniformly discretized. More...
 
- Public Member Functions inherited from pilz_industrial_motion_planner::TrajectoryBlender
 TrajectoryBlender (const pilz_industrial_motion_planner::LimitsContainer &planner_limits)
 
virtual ~TrajectoryBlender ()
 

Additional Inherited Members

- Protected Attributes inherited from pilz_industrial_motion_planner::TrajectoryBlender
const pilz_industrial_motion_planner::LimitsContainer limits_
 

Detailed Description

Trajectory blender implementing transition window algorithm.

See doc/MotionBlendAlgorithmDescription.pdf for a mathematical description of the algorithm.

Definition at line 52 of file trajectory_blender_transition_window.h.

Constructor & Destructor Documentation

◆ TrajectoryBlenderTransitionWindow()

pilz_industrial_motion_planner::TrajectoryBlenderTransitionWindow::TrajectoryBlenderTransitionWindow ( const LimitsContainer planner_limits)
inline

Definition at line 55 of file trajectory_blender_transition_window.h.

◆ ~TrajectoryBlenderTransitionWindow()

pilz_industrial_motion_planner::TrajectoryBlenderTransitionWindow::~TrajectoryBlenderTransitionWindow ( )
inlineoverride

Definition at line 60 of file trajectory_blender_transition_window.h.

Member Function Documentation

◆ blend()

bool pilz_industrial_motion_planner::TrajectoryBlenderTransitionWindow::blend ( const planning_scene::PlanningSceneConstPtr &  planning_scene,
const pilz_industrial_motion_planner::TrajectoryBlendRequest req,
pilz_industrial_motion_planner::TrajectoryBlendResponse res 
)
overridevirtual

Blend two trajectories using transition window. The trajectories have to be equally and uniformly discretized.

Parameters
planning_sceneThe scene planning is occurring in.
reqfollowing fields need to be filled for a valid request:
  • group_name : name of the planning group
  • link_name : name of the target link
  • first_trajectory: Joint trajectory stops at end point. The last point must be the same as the first point of the second trajectory.
  • second trajectory: Joint trajectory stops at end point. The first point must be the same as the last point of the first trajectory.
  • blend_radius: The blend radius determines a sphere with the intersection point of the two trajectories as the center. Trajectory blending happens inside of this sphere.
resfollowing fields are returned as response by the blend algorithm
  • group_name : name of the planning group
  • first_trajectory: Part of the first original trajectory which is outside of the blend sphere.
  • blend_trajectory: Joint trajectory connecting the first and second trajectories without stop. The first waypoint has non-zero time from start.
  • second trajectory: Part of the second original trajectory which is outside of the blend sphere. The first waypoint has non-zero time from start. error_code: information of failed blend
Returns
true if succeed

Implements pilz_industrial_motion_planner::TrajectoryBlender.

Definition at line 49 of file trajectory_blender_transition_window.cpp.

Here is the call graph for this function:

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