Flat Object Grasping Library (FOG)  0.2.1
 All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Friends Groups Pages
fog::Object Class Reference

Represents the target object as it is considered in the FOG framework. More...

#include <fog/object.h>

Public Types

enum  Type { FLAT = 0, TWODIM = 1, NONFLAT = 2 }
 The type of the object (Flat, Two dimensional or non-flat as defined by function $\phi(d, \mathcal{H})$. More...
 

Public Member Functions

 Object (const PointCloud &the_point_cloud)
 
 ~Object ()
 
void extract (const Surface &surface)
 
Object::Type checkFlatness (const Surface &surface)
 
std::vector< Eigen::Vector3d > extractOpposableDirections (const Surface &surface)
 
void filterPointCloud (const Eigen::Vector4f &leaf_size)
 

Public Attributes

std::string label
 The name/label of the object, if it is known. More...
 
pcl::PointCloud< pcl::PointXYZ > point_cloud
 The full point cloud of the object. Represents the set of points $\mathbf{o}_{p, i}$. More...
 
Eigen::Vector3d position
 The position of the object w.r.t. the world frame. More...
 
Eigen::Quaterniond orientation
 The orientation of the object w.r.t. the world frame. More...
 
Eigen::Vector3d bounding_box
 The bounding box of the object. Represents the vector $\mathbf{o}_b$. More...
 
std::vector< Eigen::Vector3d > usable_directions
 The set of the usable directions $\mathcal{O}_u$. More...
 
Type flatness
 

Friends

std::ostream & operator<< (std::ostream &, const Object &)
 

Detailed Description

Represents the target object as it is considered in the FOG framework.

Member Enumeration Documentation

The type of the object (Flat, Two dimensional or non-flat as defined by function $\phi(d, \mathcal{H})$.

Enumerator
FLAT 

The object is flat.

TWODIM 

The object is two-dimentional.

NONFLAT 

The object is non-flat.

Constructor & Destructor Documentation

fog::Object::Object ( const PointCloud the_point_cloud)
fog::Object::~Object ( )
inline

Member Function Documentation

Object::Type fog::Object::checkFlatness ( const Surface surface)
void fog::Object::extract ( const Surface surface)

+ Here is the call graph for this function:

std::vector< Eigen::Vector3d > fog::Object::extractOpposableDirections ( const Surface surface)
void fog::Object::filterPointCloud ( const Eigen::Vector4f &  leaf_size)

+ Here is the call graph for this function:

Friends And Related Function Documentation

std::ostream& operator<< ( std::ostream &  s,
const Object object 
)
friend

Member Data Documentation

Eigen::Vector3d fog::Object::bounding_box

The bounding box of the object. Represents the vector $\mathbf{o}_b$.

Type fog::Object::flatness
std::string fog::Object::label

The name/label of the object, if it is known.

Eigen::Quaterniond fog::Object::orientation

The orientation of the object w.r.t. the world frame.

pcl::PointCloud<pcl::PointXYZ> fog::Object::point_cloud

The full point cloud of the object. Represents the set of points $\mathbf{o}_{p, i}$.

Eigen::Vector3d fog::Object::position

The position of the object w.r.t. the world frame.

std::vector<Eigen::Vector3d> fog::Object::usable_directions

The set of the usable directions $\mathcal{O}_u$.