MoveIt Pro Behavior
Core Behaviors for MoveIt Pro
moveit_studio::behaviors::SetupMtcPlaceFromPose Class Referencefinal

Given an existing MTC Task object and a target grasp pose, appends MTC stages to describe a motion plan to approach, grasp, and lift an object at that pose. More...

#include <setup_mtc_place_from_pose.hpp>

Inheritance diagram for moveit_studio::behaviors::SetupMtcPlaceFromPose:
Collaboration diagram for moveit_studio::behaviors::SetupMtcPlaceFromPose:

Public Member Functions

 SetupMtcPlaceFromPose (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 
BT::NodeStatus tick () override
 
- Public Member Functions inherited from moveit_studio::behaviors::SharedResourcesNode< BT::SyncActionNode >
 SharedResourcesNode (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 Constructor for SharedResourcesNode. Called by BT::BehaviorTreeFactory when creating a new behavior tree containing this node. More...
 

Static Public Member Functions

static BT::PortsList providedPorts ()
 
static BT::KeyValueVector metadata ()
 

Additional Inherited Members

- Protected Attributes inherited from moveit_studio::behaviors::SharedResourcesNode< BT::SyncActionNode >
std::shared_ptr< BehaviorContextshared_resources_
 

Detailed Description

Given an existing MTC Task object and a target grasp pose, appends MTC stages to describe a motion plan to approach, grasp, and lift an object at that pose.

Data Port Name Port Type Object Type
task Bidirectional std::shared_ptr<moveit::task_constructor::Task>
grasp_pose Input geometry_msgs::msg::PoseStamped

Constructor & Destructor Documentation

◆ SetupMtcPlaceFromPose()

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

Member Function Documentation

◆ metadata()

BT::KeyValueVector moveit_studio::behaviors::SetupMtcPlaceFromPose::metadata ( )
static

◆ providedPorts()

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

◆ tick()

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

Allow Collision since the hand holds a collision object

Move To Pre-Place Pose

Approach Place Pose

Generate the Inverse Kinematics (IK) solutions to move to the pose specified in the "place_pose" input port. This will generate up to kMaxIKSolutions IK solution candidates to sample from, unless the timeout specified in kIKTimeoutSeconds is reached first. Collision checking is ignored for IK pose generation. Solutions that result in forbidden collisions will be eliminated by failures in the stages before and after this one.

Allow Collision This stage allows collisions between the gripper and object for stages after this one (during the Close Hand, Lift, and Retreat stages).

Open Hand

Forbid Collision This stage forbids collisions between the gripper and the object for subsequent stages.

Retreat


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