MoveIt Studio Behavior  2.1.1
Core Behaviors for the MoveIt Studio Application
moveit_studio::behaviors::SetupMTCAffordanceTemplate Class Referencefinal

A MTC-based behavior to execute motion based on an affordance template (AT). More...

#include <setup_mtc_affordance_template.hpp>

Inheritance diagram for moveit_studio::behaviors::SetupMTCAffordanceTemplate:
Collaboration diagram for moveit_studio::behaviors::SetupMTCAffordanceTemplate:

Public Member Functions

 SetupMTCAffordanceTemplate (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 
BT::NodeStatus tick () override
 

Static Public Member Functions

static BT::PortsList providedPorts ()
 

Detailed Description

A MTC-based behavior to execute motion based on an affordance template (AT).

The following parameters are used to configure MTC stages added by this Behavior:

  • ARM_GROUP_NAME: group name used for planning
  • END_EFFECTOR_GROUP_NAME: group name for end effector, used to Open/Close gripper
  • END_EFFECTOR_NAME: name of end effector
  • IK_FRAME_NAME: frame name of the grasp pose, used for IK and relative motion planning
  • END_EFFECTOR_CLOSED_POSE_NAME: name of pose target for closing the gripper
  • END_EFFECTOR_OPEN_POSE_NAME: name of pose target for opening the gripper
  • APPROACH_DISTANCE: standoff distance in the gripper Z+ axis to move to before grasping and after releasing the object
  • GRASP_POSE: the pose to grasp at (defined w.r.t. the root_frame)
  • SCREW_ORIGIN_POSE: pose. Origin of screw axis (should be in affordance or planning frame)
  • SCREW_AXIS_POSE: pose. Second pose needed to define axis (should be in affordance or planning frame)
  • TRANSLATION_DISTANCE: double. Distance to translate along axis (meters)
  • ROTATION_DISTANCE: double. Distance to rotate along axis (degrees)
  • USE_CIRCULAR_ARC: boolean. If true, move in circular arc centered at the screw origin; else use a linear path.

High-level sequence of steps: 1) Get the current state 2) Move to the approach pose 3) Allow collisions 4) Move to the grasp pose 5) Close Gripper 6) Perform affordance move 7) Open Gripper 8) Withdraw/retreat from the grasp 9) Forbid collisions

Data Port Name Port Type Object Type
task Bidirectional std::shared_ptr<moveit::task_constructor::Task>
grasp_pose Input geometry_msgs::msg::PoseStamped
screw_origin_pose Input geometry_msgs::msg::PoseStamped
screw_axis_pose Input geometry_msgs::msg::PoseStamped
translation_distance Input double
rotation_distance Input double
use_circular_arc Input bool

Constructor & Destructor Documentation

◆ SetupMTCAffordanceTemplate()

moveit_studio::behaviors::SetupMTCAffordanceTemplate::SetupMTCAffordanceTemplate ( const std::string &  name,
const BT::NodeConfiguration &  config,
const std::shared_ptr< BehaviorContext > &  shared_resources 
)

Member Function Documentation

◆ providedPorts()

BT::PortsList moveit_studio::behaviors::SetupMTCAffordanceTemplate::providedPorts ( )
static

◆ tick()

BT::NodeStatus moveit_studio::behaviors::SetupMTCAffordanceTemplate::tick ( )
override

Move To Selected Point

Open Hand

Allow Collision

Approach Grasp

Generate Pose at Grasp Point

Close Hand

Perform the affordance motion

Open Hand

Retreat from Grasp

Forbid Collision


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