Static Public Member Functions | List of all members
BoundingVolumeCalculator Class Reference

Static functions to compute point cloud bounding boxes for pick-and-place. More...

#include <bounding_volume_calculator.h>

Static Public Member Functions

static rail_manipulation_msgs::BoundingVolume computeBoundingVolume (sensor_msgs::PointCloud2 cloud)
 Fit a z-axis-aligned bounding box to x-y plane principal direction of point cloud. More...
 
static rail_manipulation_msgs::BoundingVolume computeBoundingVolume (pcl::PointCloud< pcl::PointXYZRGB >::Ptr cloud)
 Fit a z-axis-aligned bounding box to x-y plane principal direction of point cloud. More...
 
static rail_manipulation_msgs::BoundingVolume computeBoundingVolume (pcl::PointCloud< pcl::PointXYZ >::Ptr cloud)
 Fit a z-axis-aligned bounding box to x-y plane principal direction of point cloud. More...
 

Detailed Description

Static functions to compute point cloud bounding boxes for pick-and-place.

Definition at line 19 of file bounding_volume_calculator.h.

Member Function Documentation

rail_manipulation_msgs::BoundingVolume BoundingVolumeCalculator::computeBoundingVolume ( sensor_msgs::PointCloud2  cloud)
static

Fit a z-axis-aligned bounding box to x-y plane principal direction of point cloud.

Parameters
cloudpoint cloud to bound
Returns
computed bounding box

Definition at line 3 of file bounding_volume_calculator.cpp.

rail_manipulation_msgs::BoundingVolume BoundingVolumeCalculator::computeBoundingVolume ( pcl::PointCloud< pcl::PointXYZRGB >::Ptr  cloud)
static

Fit a z-axis-aligned bounding box to x-y plane principal direction of point cloud.

Parameters
cloudpoint cloud to bound
Returns
computed bounding box

Definition at line 15 of file bounding_volume_calculator.cpp.

rail_manipulation_msgs::BoundingVolume BoundingVolumeCalculator::computeBoundingVolume ( pcl::PointCloud< pcl::PointXYZ >::Ptr  cloud)
static

Fit a z-axis-aligned bounding box to x-y plane principal direction of point cloud.

Parameters
cloudpoint cloud to bound
Returns
computed bounding box

Definition at line 24 of file bounding_volume_calculator.cpp.


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


rail_segmentation
Author(s): Russell Toris , David Kent
autogenerated on Sun Feb 16 2020 04:02:44