Object represents a segmented object on a surface. More...
#include <object.h>
Public Attributes | |
| pcl::PointCloud < pcl::PointXYZRGB >::Ptr | cloud |
| A pointer to the point cloud from which this object was segmented. | |
| geometry_msgs::Vector3 | dimensions |
| The dimensions of the oriented bounding box around the object. | |
| pcl::PointIndices::Ptr | indices |
| The indices of the point cloud that this object comprises. | |
| geometry_msgs::PoseStamped | pose_stamped |
| The pose of the object. | |
| pcl::PointCloud<pcl::PointXYZRGB>::Ptr surface_perception::Object::cloud |
| pcl::PointIndices::Ptr surface_perception::Object::indices |
| geometry_msgs::PoseStamped surface_perception::Object::pose_stamped |
The pose of the object.
The origin is at the center of the oriented bounding box around the object. The z direction points "up" relative to the surface, while the x and y directions are parallel to the sides of the box. There are no other constraints for which direction is x or y.