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

This class represents a behavior that can calculate the pose of a door lever handle along with its depth and length. The convention is that the Z-axis of the pose represents the axis of rotation of the handle. The X-axis points along the handle and points toward the door hinge. More...

#include <get_door_handle.hpp>

Inheritance diagram for moveit_studio::behaviors::GetDoorHandlePose:
Collaboration diagram for moveit_studio::behaviors::GetDoorHandlePose:

Public Member Functions

 GetDoorHandlePose (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 
BT::NodeStatus onStart () override
 
BT::NodeStatus onRunning () override
 method invoked by an action in the RUNNING state. More...
 
void onHalted () override
 
- 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. 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::StatefulActionNode >
std::shared_ptr< BehaviorContextshared_resources_
 

Detailed Description

This class represents a behavior that can calculate the pose of a door lever handle along with its depth and length. The convention is that the Z-axis of the pose represents the axis of rotation of the handle. The X-axis points along the handle and points toward the door hinge.

Data Port Name Port Type Object Type
point_cloud input sensor_msgs::msg::PointCloud2
handle_poses input std::vector<geometry_msgs::msg::PoseStamped>
minimum_door_handle_depth input double
target_output_frame_id input std::string
target_handle_pose output geometry_msgs::msg::PoseStamped
target_handle_z_offset output double
target_handle_length output double

Constructor & Destructor Documentation

◆ GetDoorHandlePose()

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

Member Function Documentation

◆ metadata()

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

◆ onHalted()

void moveit_studio::behaviors::GetDoorHandlePose::onHalted ( )
override

◆ onRunning()

BT::NodeStatus moveit_studio::behaviors::GetDoorHandlePose::onRunning ( )
override

method invoked by an action in the RUNNING state.

◆ onStart()

BT::NodeStatus moveit_studio::behaviors::GetDoorHandlePose::onStart ( )
override

◆ providedPorts()

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

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