MoveIt Pro API
Core Behaviors for MoveIt Pro
Loading...
Searching...
No Matches
moveit_studio::behaviors::GetGraspPoseFromPointCloud Class Referencefinal

Infer grasp pose from point cloud of an object. More...

#include <l2g_grasping.hpp>

Inheritance diagram for moveit_studio::behaviors::GetGraspPoseFromPointCloud:
Collaboration diagram for moveit_studio::behaviors::GetGraspPoseFromPointCloud:

Classes

struct  InferenceHandle
 Allows different models to be used with behavior. More...
 
struct  L2GHandle
 Uses L2G for grasp inference. More...
 

Public Member Functions

 GetGraspPoseFromPointCloud (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< moveit_studio::behaviors::BehaviorContext > &shared_resources, std::unique_ptr< InferenceHandle > model=std::make_unique< L2GHandle >())
 Constructs the behavior for inferring grasps from point clouds.
 
 ~GetGraspPoseFromPointCloud () final
 
- Public Member Functions inherited from moveit_studio::behaviors::AsyncBehaviorBase
 AsyncBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 
virtual ~AsyncBehaviorBase ()=default
 
BT::NodeStatus onStart () override
 Required implementation of BT::StatefulActionNode::onStart().
 
BT::NodeStatus onRunning () override
 Required implementation of BT::StatefulActionNode::onRunning().
 
void onHalted () override
 Required implementation of BT::StatefulActionNode::onHalted().
 
void resetStatus ()
 Resets the internal status of this node.
 
- Public Member Functions inherited from moveit_studio::behaviors::SharedResourcesNode< BT::StatefulActionNode >
 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 ()
 Implementation of the required providedPorts() function for the Behavior.
 
static BT::KeyValueVector metadata ()
 Implementation of the metadata() function for displaying metadata, such as Behavior description and subcategory, in the MoveIt Studio Developer Tool.
 

Protected Member Functions

tl::expected< bool, std::string > doWork () override
 User-implemented function which handles executing the potentially-long-running process.
 
- Protected Member Functions inherited from moveit_studio::behaviors::AsyncBehaviorBase
virtual tl::expected< void, std::string > doHalt ()
 Optionally implement additional work needed to cleanly interrupt the async process.
 
void notifyCanHalt ()
 Called when runAsync() finishes to notify onHalted() that the async process has finished.
 

Additional Inherited Members

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

Detailed Description

Infer grasp pose from point cloud of an object.

Constructor & Destructor Documentation

◆ GetGraspPoseFromPointCloud()

moveit_studio::behaviors::GetGraspPoseFromPointCloud::GetGraspPoseFromPointCloud ( const std::string &  name,
const BT::NodeConfiguration &  config,
const std::shared_ptr< moveit_studio::behaviors::BehaviorContext > &  shared_resources,
std::unique_ptr< InferenceHandle model = std::make_unique<L2GHandle>() 
)

Constructs the behavior for inferring grasps from point clouds.

Parameters
nameof a particular instance of this Behavior. This will be set by the behavior tree factory when this Behavior is created within a new behavior tree.
configfor this Behavior, such as the mapping between the Behavior's data ports on the behavior tree's blackboard. This will be set by the behavior tree factory when this Behavior is created within a new behavior tree.
modelthat does the grasp inference.

An important limitation is that the members of the base Behavior class are not instantiated until after the initialize() function is called, so these classes should not be used within the constructor.

◆ ~GetGraspPoseFromPointCloud()

moveit_studio::behaviors::GetGraspPoseFromPointCloud::~GetGraspPoseFromPointCloud ( )
final

Ensures the model finishes gracefully

Member Function Documentation

◆ doWork()

tl::expected< bool, std::string > moveit_studio::behaviors::GetGraspPoseFromPointCloud::doWork ( )
overrideprotectedvirtual

User-implemented function which handles executing the potentially-long-running process.

This function is called within an async process in a separate thread.

Returns
A tl::expected which contains a bool indicating task success if the process completed successfully or was canceled, or an error message if the process failed unexpectedly.

Implements moveit_studio::behaviors::AsyncBehaviorBase.

◆ metadata()

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

Implementation of the metadata() function for displaying metadata, such as Behavior description and subcategory, in the MoveIt Studio Developer Tool.

Returns
A BT::KeyValueVector containing the Behavior metadata.

◆ providedPorts()

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

Implementation of the required providedPorts() function for the Behavior.

The BehaviorTree.CPP library requires that Behaviors must implement a static function named providedPorts() which defines their input and output ports. If the Behavior does not use any ports, this function must return an empty BT::PortsList. This function returns a list of ports with their names and port info, which is used internally by the behavior tree.

Returns
List of ports for the behavior.

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