![]() |
MoveIt Pro API
Core Behaviors for MoveIt Pro
|
Configures MTC stages to grasp a location, rotate the end-effector about an axis to turn the grasp point (for example a handle), and then push the end-effector away from the robot base while still grasping (for example to open a door). More...
#include <setup_mtc_grasp_and_twist_then_move_along_arc_push.hpp>
Public Member Functions | |
SetupMTCGraspAndTwistThenMoveAlongArcPush (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) | |
BT::NodeStatus | tick () override |
![]() | |
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. | |
Static Public Member Functions | |
static BT::PortsList | providedPorts () |
static BT::KeyValueVector | metadata () |
Additional Inherited Members | |
![]() | |
std::shared_ptr< BehaviorContext > | shared_resources_ |
Configures MTC stages to grasp a location, rotate the end-effector about an axis to turn the grasp point (for example a handle), and then push the end-effector away from the robot base while still grasping (for example to open a door).
The input data ports are generally calculated by separate perception processing Behaviors in a previous step of the Objective.
Data Port Name | Port Type | Object Type |
---|---|---|
task | Bidirectional | std::shared_ptr<moveit::task_constructor::Task> |
graspable_object | Input | moveit_studio_vision_msgs::msg::GraspableObject |
handle_z_offset | Input | double |
handle_length | Input | double |
approach_distance | Input | double |
push_open_distance | Input | double |
move_distance | Input | double |
use_circular_arc | Input | bool |
monitored_stage | Input | std::string |
moveit_studio::behaviors::SetupMTCGraspAndTwistThenMoveAlongArcPush::SetupMTCGraspAndTwistThenMoveAlongArcPush | ( | const std::string & | name, |
const BT::NodeConfiguration & | config, | ||
const std::shared_ptr< BehaviorContext > & | shared_resources | ||
) |
|
static |
|
static |
|
override |
Move To Approach Pose
Generate Pose at Approach Pose
Allow Collision
Approach Grasp
Rotate the door handle
Calculate affordance poses
Push door
move off the door handle
retract from door
Forbid Collision