Given a point cloud and a sphere-shaped region of interest, create a new point cloud which contains only the points that are inside the region of interest. The dimensions and size of the region of interest are defined relative to its centroid.
More...
#include <crop_points_in_sphere.hpp>
|
| CropPointsInSphere (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(). 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...
|
|
| 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...
|
|
Given a point cloud and a sphere-shaped region of interest, create a new point cloud which contains only the points that are inside the region of interest. The dimensions and size of the region of interest are defined relative to its centroid.
Data Port Name | Port Type | Object Type |
point_cloud | input | sensor_msgs::msg::PointCloud2 |
crop_sphere_centroid_pose | input | geometry_msgs::msg::PoseStamped |
crop_sphere_radius | input | std::vector<double> |
point_cloud_cropped | output | sensor_msgs::msg::PointCloud2 |
◆ CropPointsInSphere()
moveit_studio::behaviors::CropPointsInSphere::CropPointsInSphere |
( |
const std::string & |
name, |
|
|
const BT::NodeConfiguration & |
config, |
|
|
const std::shared_ptr< BehaviorContext > & |
shared_resources |
|
) |
| |
◆ metadata()
BT::KeyValueVector moveit_studio::behaviors::CropPointsInSphere::metadata |
( |
| ) |
|
|
static |
◆ providedPorts()
BT::PortsList moveit_studio::behaviors::CropPointsInSphere::providedPorts |
( |
| ) |
|
|
static |
The documentation for this class was generated from the following files: