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

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...

#include <fog/models.h>

Public Member Functions

 ObjectSurfaceCombination (double point_cloud_filtering, double non_convex_dlambda, double non_convex_mu, double feasible_dlambda, double feasible_mu, double far_point_distance, double nr_far_points, double feasible_directions_centroid_filter)
 
 ~ObjectSurfaceCombination ()
 
void extract (const Object &object, const Surface &surface)
 Extracts the object-surface combination. More...
 
void calcNonConvexPoints (const PointCloud &object, const Surface &surface, double dlambda, double mu)
 Calculates the non convex points, i.e. the set $\mathcal{N}$ (Eq. (11) [1]). More...
 
void calcFeasibleNonConvexPoints (const Vector3 &surface_normal, double dlambda, double mu)
 Calculates set of pairs of the feasible non-convex points $\mathcal{N}_f$ (Eq. (14), (15) [1]). More...
 

Public Attributes

PointCloud object_projection
 The object's projection on the support surface. Represents the set $\mathcal{S}_O$ (Eq. (9) [1]) More...
 
PointCloud object_projection_union
 The union of the object projection and the object. Represents the set $\mathcal{A} =\mathcal{S}_O \cup \mathcal{O}$. More...
 
PointCloud non_convex_points
 The set of the non convex points. Represents the set $\mathcal{N}$ (Eq. (11) [1]). More...
 
PointCloud non_convex_points_projected
 The set of the non convex points projected onto the surface. More...
 
std::vector< std::pair< Point3,
Point3 > > 
feasible_pairs_set
 The set of pairs of the feasible non-convex points. Represents the set $\mathcal{N}_f$ given by Eq. (14), (15) [1]. More...
 

Private Attributes

double point_cloud_filtering
 
double non_convex_dlambda
 
double non_convex_mu
 
double feasible_dlambda
 
double feasible_mu
 
double far_point_distance
 
double nr_far_points
 
double feasible_directions_centroid_filter
 

Detailed Description

Represents the object-surface combination as it is considered in the FOG framework, i.e. the set of non-convex directions $\mathcal{N}_f$.

Constructor & Destructor Documentation

fog::ObjectSurfaceCombination::ObjectSurfaceCombination ( double  point_cloud_filtering,
double  non_convex_dlambda,
double  non_convex_mu,
double  feasible_dlambda,
double  feasible_mu,
double  far_point_distance,
double  nr_far_points,
double  feasible_directions_centroid_filter 
)
fog::ObjectSurfaceCombination::~ObjectSurfaceCombination ( )
inline

Member Function Documentation

void fog::ObjectSurfaceCombination::calcFeasibleNonConvexPoints ( const Vector3 surface_normal,
double  dlambda,
double  mu 
)

Calculates set of pairs of the feasible non-convex points $\mathcal{N}_f$ (Eq. (14), (15) [1]).

The final result is written in fog::ObjectSurfaceCombination::feasible_pairs_set.

Parameters
surface_normalThe surface normal.
dlambdaThe lambda step for the line segments.
Theparameter $\mu$ for the clearence of the path.

+ Here is the call graph for this function:

void fog::ObjectSurfaceCombination::calcNonConvexPoints ( const PointCloud object,
const Surface surface,
double  dlambda,
double  mu 
)

Calculates the non convex points, i.e. the set $\mathcal{N}$ (Eq. (11) [1]).

The final result is written in ObjectSurfaceCombination::non_convex_points.

Parameters
objectThe point cloud of the object.
surfaceThe support surface.
dlambdaThe step for discritizing line segments
muThe parameter $\mu$ dependent on the hand in use.
See Also
fog::getPointInLineSegment

+ Here is the call graph for this function:

void fog::ObjectSurfaceCombination::extract ( const Object object,
const Surface surface 
)

Extracts the object-surface combination.

Parameters
objectThe model of the object
surfaceThe model of the surface
See Also
fog::Object, fog::Surface

+ Here is the call graph for this function:

Member Data Documentation

double fog::ObjectSurfaceCombination::far_point_distance
private
double fog::ObjectSurfaceCombination::feasible_directions_centroid_filter
private
double fog::ObjectSurfaceCombination::feasible_dlambda
private
double fog::ObjectSurfaceCombination::feasible_mu
private
std::vector<std::pair<Point3, Point3> > fog::ObjectSurfaceCombination::feasible_pairs_set

The set of pairs of the feasible non-convex points. Represents the set $\mathcal{N}_f$ given by Eq. (14), (15) [1].

The first element is $\mathbf{p}_R$ and the second $\mathbf{p}_N$.

double fog::ObjectSurfaceCombination::non_convex_dlambda
private
double fog::ObjectSurfaceCombination::non_convex_mu
private
PointCloud fog::ObjectSurfaceCombination::non_convex_points

The set of the non convex points. Represents the set $\mathcal{N}$ (Eq. (11) [1]).

PointCloud fog::ObjectSurfaceCombination::non_convex_points_projected

The set of the non convex points projected onto the surface.

double fog::ObjectSurfaceCombination::nr_far_points
private
PointCloud fog::ObjectSurfaceCombination::object_projection

The object's projection on the support surface. Represents the set $\mathcal{S}_O$ (Eq. (9) [1])

PointCloud fog::ObjectSurfaceCombination::object_projection_union

The union of the object projection and the object. Represents the set $\mathcal{A} =\mathcal{S}_O \cup \mathcal{O}$.

double fog::ObjectSurfaceCombination::point_cloud_filtering
private