|
Flat Object Grasping Library (FOG)
0.2.1
|
Represents the object-surface combination as it is considered in the FOG framework, i.e. the set of non-convex directions
.
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 (Eq. (11) [1]). More... | |
| void | calcFeasibleNonConvexPoints (const Vector3 &surface_normal, double dlambda, double mu) |
Calculates set of pairs of the feasible non-convex points (Eq. (14), (15) [1]). More... | |
Public Attributes | |
| PointCloud | object_projection |
The object's projection on the support surface. Represents the set (Eq. (9) [1]) More... | |
| PointCloud | object_projection_union |
The union of the object projection and the object. Represents the set . More... | |
| PointCloud | non_convex_points |
The set of the non convex points. Represents the set (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 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 |
Represents the object-surface combination as it is considered in the FOG framework, i.e. the set of non-convex directions
.
| 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 | ||
| ) |
|
inline |
| void fog::ObjectSurfaceCombination::calcFeasibleNonConvexPoints | ( | const Vector3 & | surface_normal, |
| double | dlambda, | ||
| double | mu | ||
| ) |
Calculates set of pairs of the feasible non-convex points
(Eq. (14), (15) [1]).
The final result is written in fog::ObjectSurfaceCombination::feasible_pairs_set.
| surface_normal | The surface normal. |
| dlambda | The lambda step for the line segments. |
| The | parameter 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
(Eq. (11) [1]).
The final result is written in ObjectSurfaceCombination::non_convex_points.
| object | The point cloud of the object. |
| surface | The support surface. |
| dlambda | The step for discritizing line segments |
| mu | The parameter dependent on the hand in use. |
Here is the call graph for this function:Extracts the object-surface combination.
| object | The model of the object |
| surface | The model of the surface |
Here is the call graph for this function:
|
private |
|
private |
|
private |
|
private |
The set of pairs of the feasible non-convex points. Represents the set
given by Eq. (14), (15) [1].
The first element is
and the second
.
|
private |
|
private |
| PointCloud fog::ObjectSurfaceCombination::non_convex_points |
The set of the non convex points. Represents the set
(Eq. (11) [1]).
| PointCloud fog::ObjectSurfaceCombination::non_convex_points_projected |
The set of the non convex points projected onto the surface.
|
private |
| PointCloud fog::ObjectSurfaceCombination::object_projection |
The object's projection on the support surface. Represents the set
(Eq. (9) [1])
| PointCloud fog::ObjectSurfaceCombination::object_projection_union |
The union of the object projection and the object. Represents the set
.
|
private |