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

The namespace having all the FOG codebase. More...

Classes

class  FingerCompliance
 Implements a controller for active compliance of the hand's fingers. More...
 
class  ReachFGSAlpha
 A class that implements the controller for reaching the FGS state for the strategy- $\alpha$. It closes the fingers. More...
 
class  ReachFGSBeta
 A class that implements the controller for reaching the FGS state for the strategy- $\beta$. It closes the fingers and moves the arm. More...
 
class  ReachPGSBeta
 A class that implements the controller for reaching the PGS state. It reads feedback from the position of the fingeres and commands the task velocity of the arm. More...
 
class  UpdateBHand
 
class  DecisionMaker
 Decides which of the available grasp strategies can be used for grasping the target object, given the current scene. More...
 
class  EnablingConditions
 The enabling conditions for the Decision Making. More...
 
class  EnabledStrategies
 The enabled strategies from the Decision Making. More...
 
class  FlatObjectGrasper
 The main class of FOG which implements the pipeline for grasping a flat object. More...
 
class  Hand
 Represents the robotic hand as it is considered in the FOG framework. More...
 
class  IGSPlanner
 Plans Initial Grasping States (IGSs) for each selected grasp strategy. More...
 
class  InitialGraspState
 Representing and Initial Grasp State. More...
 
class  Interface
 Abstract class which defines the interfaces with FOG. More...
 
class  Models
 The FOG Models. More...
 
class  Object
 Represents the target object as it is considered in the FOG framework. More...
 
class  ObjectSurfaceCombination
 Represents the object-surface combination as it is considered in the FOG framework, i.e. the set of non-convex directions $\mathcal{N}_f$. More...
 
struct  HandParams
 
class  ObjectSurfaceCombinationParams
 Parameters related to the FOG object-surface combination. More...
 
struct  ControllersParams
 
class  RobotParams
 Parameters related to the robot configuration that is used. If it is real or a simulated hardware. More...
 
class  BetaParams
 Parameters related to strategy- $\beta$. More...
 
class  GammaParams
 Parameters related to strategy- $\gamma$. More...
 
class  Params
 The FOG parameters. More...
 
class  Surface
 Represents the support surface as it is considered in the FOG framework, as rectangle with 4 limits. More...
 
class  RVisualizer
 Visualizes in RViz FOG models. In order to see the models, add in your RViz configuration a PointCloud2 panel with the point cloud topic name and a MarkerArray with the rviz_topic that you initialize the class. More...
 

Typedefs

typedef pcl::PointCloud
< pcl::PointXYZ > 
PointCloud
 The type used by FOG as a Point Cloud ( $\in \mathbb{R}^{n\times 3}$) More...
 
typedef Eigen::Vector3d Point3
 The type used by FOG as a Point in 3D space ( $\in \mathbb{R}^{3}$) More...
 
typedef Eigen::Vector3d Vector3
 The type used by FOG as a Vector in 3D space ( $\in \mathbb{R}^{3}$) More...
 
typedef Eigen::Affine3d Pose
 The type used by FOG as a Vector as a P ( $\in SE(3)$) More...
 
typedef Eigen::Quaterniond Quaternion
 The type used by FOG as a Vector as a P ( $\in SE(3)$) More...
 

Enumerations

enum  Strategy { ALPHA, BETA, GAMMA }
 Lists of the available grasp strategies in FOG. More...
 
enum  FrameLabel { PALM, TIP1, TIP2, TIP3 }
 Defines the available frames considered in FOG framework. More...
 

Functions

Point3 getPointInLineSegment (const Point3 &p1, const Point3 &p2, double lambda)
 Returns a 3D point in the line segment between two points. More...
 
void filterPointCloud (const Eigen::Vector4f &leaf_size, PointCloud &point_cloud)
 Downsamples a point cloud using PCL's Voxel Grid. More...
 
Point3 projectPointToSurface (const Point3 &point, const Point3 &surface_point, const Vector3 surface_normal)
 Projects orthogonally a 3D point onto a plane given a point of the plane and its normal vector. In implements Eq. (10) [1]. More...
 
void projectPointCloudOnSurface (const PointCloud &point_cloud, const Point3 &surface_point, const Vector3 surface_normal, PointCloud &result)
 Projects a point cloud on to a plane defined by its normal vector and a point which belongs on the plane. More...
 
pcl::PointXYZ toPCLPointXYZ (const Eigen::Vector3d &eigen)
 Mapping of an Eigen Vector to a PCL Point XYZ. More...
 
double getDistanceFromNearestNeighbor (const PointCloud::Ptr &cloud, const Point3 &point)
 Returns the minimum distance of the given point from the given point cloud, using a K-NN Search for one neighbor. More...
 
std::vector< Point3getPointsFarFromGiven (const Point3 &point, double radius, const Vector3 &normal, unsigned int nr_points)
 Provides points far from the one by sampling a circular curve with radius r, centered in the given point and parallel to the plane which is defined by its normal. Implements the set $\mathcal{R}$ of Eq. (13) More...
 
bool isTheLinearPathClearBetweenTwoPoints (const Point3 &p1, const Point3 &p2, const PointCloud::Ptr &point_cloud, double dlambda, double mu)
 Checks if the linear path is clear betweein two points. More...
 
void graspObject ()
 
void extractBoundingBox (const PointCloud &point_cloud, Eigen::Vector3d &translation, Eigen::Quaterniond &rotation, Eigen::Vector3d &dimensions)
 Extracts the oriented bounding box of the given point cloud. More...
 
std::ostream & operator<< (std::ostream &s, const EnabledStrategies &strategies)
 
std::ostream & operator<< (std::ostream &s, const EnablingConditions &e)
 
std::ostream & operator<< (std::ostream &s, const Hand &hand)
 
std::ostream & operator<< (std::ostream &s, const Object &object)
 
std::ostream & operator<< (std::ostream &s, const Surface &surface)
 

Detailed Description

The namespace having all the FOG codebase.

Typedef Documentation

typedef Eigen::Vector3d fog::Point3

The type used by FOG as a Point in 3D space ( $\in \mathbb{R}^{3}$)

typedef pcl::PointCloud<pcl::PointXYZ> fog::PointCloud

The type used by FOG as a Point Cloud ( $\in \mathbb{R}^{n\times 3}$)

typedef Eigen::Affine3d fog::Pose

The type used by FOG as a Vector as a P ( $\in SE(3)$)

typedef Eigen::Quaterniond fog::Quaternion

The type used by FOG as a Vector as a P ( $\in SE(3)$)

typedef Eigen::Vector3d fog::Vector3

The type used by FOG as a Vector in 3D space ( $\in \mathbb{R}^{3}$)

Enumeration Type Documentation

Defines the available frames considered in FOG framework.

Enumerator
PALM 

The frame of the palm of the hand.

TIP1 

The frame of the tip of the finger 1.

TIP2 

The frame of the tip of the finger 2.

TIP3 

The frame of the tip of the finger 3.

Lists of the available grasp strategies in FOG.

Enumerator
ALPHA 

Strategy- $\alpha$ as described in Section III-A [1].

BETA 

Strategy- $\beta$ as described in Section III-B [1].

GAMMA 

Strategy- $\gamma$ as described in Section III-C [1].

Function Documentation

void fog::extractBoundingBox ( const PointCloud &  point_cloud,
Eigen::Vector3d &  translation,
Eigen::Quaterniond &  rotation,
Eigen::Vector3d &  dimensions 
)

Extracts the oriented bounding box of the given point cloud.

Parameters
point_cloudThe point cloud as input.
translationThe translation of the bounding box as output.
rotationThe orientation of the bounding box as output.
dimensionsThe dimensions of the bounding box (x, y, z) wrt its own reference frame
void fog::filterPointCloud ( const Eigen::Vector4f &  leaf_size,
PointCloud &  point_cloud 
)

Downsamples a point cloud using PCL's Voxel Grid.

Parameters
leaf_sizeThe leaf size for the Voxel Grid in meters. It denotes the volume (x, y, z) which will include one point.
point_cloudThe point cloud to be sampled. This is the output.
double fog::getDistanceFromNearestNeighbor ( const PointCloud::Ptr &  cloud,
const Point3 &  point 
)

Returns the minimum distance of the given point from the given point cloud, using a K-NN Search for one neighbor.

Parameters
cloudThe point cloud
pointThe point
Point3 fog::getPointInLineSegment ( const Point3 &  p1,
const Point3 &  p2,
double  lambda 
)
inline

Returns a 3D point in the line segment between two points.

Implements the line segment: $ [\mathbf{p_1}, \mathbf{p_2}] = \{\mathbf{p} \in \mathbb{R}^3 \; | \; \mathbf{p} = (1-\lambda)\mathbf{p}_1 + \lambda \mathbf{p}_2, 0 \leq \lambda \leq 1\} $

Parameters
p1The first point of the line segment.
p2The second point of the line segment.
lambdaThe value of the parameter $\lambda$
std::vector< Point3 > fog::getPointsFarFromGiven ( const Point3 &  point,
double  radius,
const Vector3 &  normal,
unsigned int  nr_points 
)

Provides points far from the one by sampling a circular curve with radius r, centered in the given point and parallel to the plane which is defined by its normal. Implements the set $\mathcal{R}$ of Eq. (13)

Parameters
pointThe given point.
radiusThe radius of the circle to be sampled.
normalThe normal vector of the plane of the circle.
no_of_pointsThe number of points to be produced
void fog::graspObject ( )
bool fog::isTheLinearPathClearBetweenTwoPoints ( const Point3 &  p1,
const Point3 &  p2,
const PointCloud::Ptr &  point_cloud,
double  dlambda,
double  mu 
)

Checks if the linear path is clear betweein two points.

Creates a discreate line segment between the two points and tests if the points in the line segments are close to the given point cloud.

Parameters
p1The first point
p2The second point
point_cloudA pointer to the point cloud which may obstract the path between p1 and p2
dlambdaThe lambda discretization parameter
muThe $f$f parameter denoting when a point is considered close to the point cloud

+ Here is the call graph for this function:

std::ostream& fog::operator<< ( std::ostream &  s,
const EnabledStrategies &  strategies 
)
std::ostream& fog::operator<< ( std::ostream &  s,
const Hand &  hand 
)
std::ostream& fog::operator<< ( std::ostream &  s,
const EnablingConditions &  e 
)
std::ostream& fog::operator<< ( std::ostream &  s,
const Surface &  surface 
)
std::ostream& fog::operator<< ( std::ostream &  s,
const Object &  object 
)
void fog::projectPointCloudOnSurface ( const PointCloud &  point_cloud,
const Point3 &  surface_point,
const Vector3  surface_normal,
PointCloud &  result 
)

Projects a point cloud on to a plane defined by its normal vector and a point which belongs on the plane.

Parameters
point_cloudThe point cloud to be projected
surface_pointA point belonging to the surface of the plane
surface_normalThe normal vector on the plane
resultThe resulted projected point cloud

+ Here is the call graph for this function:

Point3 fog::projectPointToSurface ( const Point3 &  point,
const Point3 &  surface_point,
const Vector3  surface_normal 
)
inline

Projects orthogonally a 3D point onto a plane given a point of the plane and its normal vector. In implements Eq. (10) [1].

Parameters
pointThe point to be projected.
surface_pointA point on the surface's plane
surface_normalThe vector of the surface normal
pcl::PointXYZ fog::toPCLPointXYZ ( const Eigen::Vector3d &  eigen)
inline

Mapping of an Eigen Vector to a PCL Point XYZ.

Parameters
eigenThe eigen vector
Returns
The equivelant PCL point