69 void setBlender(std::unique_ptr<pilz_industrial_motion_planner::TrajectoryBlender> blender);
74 void setModel(
const moveit::core::RobotModelConstPtr& model);
100 const robot_trajectory::RobotTrajectoryPtr& other,
const double blend_radius);
110 std::vector<robot_trajectory::RobotTrajectoryPtr>
build()
const;
113 void blend(
const planning_scene::PlanningSceneConstPtr&
planning_scene,
114 const robot_trajectory::RobotTrajectoryPtr& other,
const double blend_radius);
131 std::unique_ptr<pilz_industrial_motion_planner::TrajectoryBlender> blender_;
134 moveit::core::RobotModelConstPtr model_;
137 robot_trajectory::RobotTrajectoryPtr traj_tail_;
140 std::vector<robot_trajectory::RobotTrajectoryPtr> traj_cont_;
144 static constexpr double ROBOT_STATE_EQUALITY_EPSILON = 1e-4;
149 blender_ = std::move(blender);
159 traj_tail_ =
nullptr;
Helper class to encapsulate the merge and blend process of trajectories.
std::vector< robot_trajectory::RobotTrajectoryPtr > build() const
void reset()
Clears the trajectory container under construction.
void setModel(const moveit::core::RobotModelConstPtr &model)
Sets the robot model needed to create new trajectory elements.
void setBlender(std::unique_ptr< pilz_industrial_motion_planner::TrajectoryBlender > blender)
Sets the blender used to blend two trajectories.
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.
Maintain a sequence of waypoints and the time durations between these waypoints.
std::function< const std::string &(const std::string &)> TipFrameFunc_t
This namespace includes the central class for representing planning contexts.
#define CREATE_MOVEIT_ERROR_CODE_EXCEPTION(EXCEPTION_CLASS_NAME, ERROR_CODE)