MoveIt Pro Behavior
Core Behaviors for MoveIt Pro
|
Loads a point cloud from a .pcd or .stl file, optionally recolors it, and writes it to an output data port. More...
#include <load_pointcloud_from_file.hpp>
Public Member Functions | |
LoadPointCloudFromFile (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) | |
![]() | |
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. | |
![]() | |
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 | |
![]() | |
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. | |
![]() | |
std::shared_ptr< BehaviorContext > | shared_resources_ |
Loads a point cloud from a .pcd or .stl file, optionally recolors it, and writes it to an output data port.
The scale, num_sampled_points, and random_seed variables are used only when reading an .stl file, since these parameters control sampling the point cloud from a mesh.
Data Port Name | Port Type | Object Type |
---|---|---|
package_name | input | std::string |
file_path | input | std::string |
frame_id | input | std::string |
scale | input | float |
num_sampled_points | input | size_t |
random_seed | input | size_t |
color | input | std::vector<uint8_t> |
point_cloud | output | sensor_msgs::msg::PointCloud2 |
moveit_studio::behaviors::LoadPointCloudFromFile::LoadPointCloudFromFile | ( | const std::string & | name, |
const BT::NodeConfiguration & | config, | ||
const std::shared_ptr< BehaviorContext > & | shared_resources | ||
) |
|
static |
|
static |