MoveIt Pro Behavior
Core Behaviors for MoveIt Pro
|
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_pick_from_pose.hpp>
Public Member Functions | |
SetupMtcPickFromPose (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< BehaviorContext > | shared_resources_ |
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 |
moveit_studio::behaviors::SetupMtcPickFromPose::SetupMtcPickFromPose | ( | const std::string & | name, |
const BT::NodeConfiguration & | config, | ||
const std::shared_ptr< BehaviorContext > & | shared_resources | ||
) |
|
static |
|
static |
|
override |
Move To Pre-Grasp Pose
Set Allowed Collisions This stage forbids collisions between the gripper and the octomap before the stage (during the Move To Pre-Grasp Pose stage, so the gripper doesn't collide with objects while moving into position), and allows them after this stage.
Approach Grasp
Set Allowed Collisions This stage allows collisions between the gripper and the octomap before the stage (during the Approach Grasp stage, so the gripper can move into the octomap), and forbids them after this stage.
Generate the Inverse Kinematics (IK) solutions to move to the pose specified in the "grasp_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).
Close Hand
Retreat