Connecting Stages

MTC provides only one connecting stage called Connect.
A connect stage solves for a feasible trajectory between the start and goal states.

Connect

The Connect stage connects two stages by finding a motion plan between the start and end goal given by the adjacent stages.
The default cost term depends on path length.
The default planning time for this stage is 1.0s.
Properties to be set by user

Property Name

Function to set property

Description

merge_mode

Define the merge strategy to use when performing planning operations. This parameter is an enum type. Can be SEQUENTIAL(Store sequential trajectories) or WAYPOINTS(Join trajectories by their waypoints). Default is WAYPOINTS.

path_constaints

void setPathConstraints(moveit_msgs/Constraints path_constraints)

Constraints to maintain during trajectory

merge_time_parameterization

Default is TOTG (Time-Optimal Trajectory Generation). Information about TOTG is available in the Time Parameterization tutorial

API doc for Connect.

Code Example

auto node = std::make_shared<rclcpp::Node>();
// planner used for connect
auto pipeline = std::make_shared<solvers::PipelinePlanner>(node, "ompl", "RRTConnectkConfigDefault");
// connect to pick
stages::Connect::GroupPlannerVector planners = { { "arm", pipeline }, { "gripper", pipeline } };
auto connect = std::make_unique<stages::Connect>("connect", planners);