MoveIt Pro Behavior
Core Behaviors for MoveIt Pro
moveit_studio::behaviors::GetPoseFromPixelCoords Class Reference

Given an ordered point cloud and normalized pixel XY coordinates, outputs a stamped pose corresponding to a point normal to the selected coordinates. More...

#include <get_pose_from_pixel_coords.hpp>

Inheritance diagram for moveit_studio::behaviors::GetPoseFromPixelCoords:
Collaboration diagram for moveit_studio::behaviors::GetPoseFromPixelCoords:

Public Member Functions

 GetPoseFromPixelCoords (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 
- 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(). More...
 
BT::NodeStatus onRunning () override
 Required implementation of BT::StatefulActionNode::onRunning(). More...
 
void onHalted () override
 Required implementation of BT::StatefulActionNode::onHalted(). More...
 
void resetStatus ()
 Resets the internal status of this node. More...
 
- 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 ()
 

Protected Member Functions

tl::expected< bool, std::string > doWork () override
 User-implemented function which handles executing the potentially-long-running process. More...
 
- 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. More...
 
void notifyCanHalt ()
 Called when runAsync() finishes to notify onHalted() that the async process has finished. More...
 

Additional Inherited Members

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

Detailed Description

Given an ordered point cloud and normalized pixel XY coordinates, outputs a stamped pose corresponding to a point normal to the selected coordinates.

This assumes that the pixel XY coordinates are normalized, i.e., have values in the range [0..1] relative to the image's height and width. Additionally, the output pose always aligns the Z axis with the normal of the plane by using the smallest eigenvalue of a planar patch with radius neighbor_radius around a selected point.

Data Port Name Port Type Object Type
point_cloud input sensor_msgs::msg::PointCloud2
pixel_coords input std::vector<geometry_msgs::msg::PointStamped>
downsample_fraction input double
neighbor_radius input double
output_poses output std::vector<geometry_msgs::msg::PoseStamped>

Constructor & Destructor Documentation

◆ GetPoseFromPixelCoords()

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

Member Function Documentation

◆ doWork()

tl::expected< bool, std::string > moveit_studio::behaviors::GetPoseFromPixelCoords::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::GetPoseFromPixelCoords::metadata ( )
static

◆ providedPorts()

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

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