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

#include <create_graspable_object.hpp>

Inheritance diagram for moveit_studio::behaviors::CreateGraspableObject:
Collaboration diagram for moveit_studio::behaviors::CreateGraspableObject:

Public Member Functions

 CreateGraspableObject (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< moveit_studio::behaviors::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

Creates a GraspableObject message (of a primitive Cuboid) given its pose given as individual points, the dimensions of the Cuboid, a frame ID, an ID for the newly created object, and whether any top, front, or side graspable faces should be generated.

Data Port Name Port Type Object Type
pose Input geometry_msgs::msg::PoseStamped
dx Input double
dy Input double
dz Input double
object_id Input std::string
generate_top_face Input bool
generate_front_face Input bool
generate_side_faces Input bool
cuboid_object Output moveit_studio_vision_msgs::msg::GraspableObject

Constructor & Destructor Documentation

◆ CreateGraspableObject()

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

Member Function Documentation

◆ metadata()

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

◆ providedPorts()

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

◆ tick()

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

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