Classes | |
class | ContactPoint |
Contains the coordinates of a ICR::TargetObject's vertex and its corresponding vertex normal, as well as a unique id and a list of id's of neighboring points. More... | |
class | DiscreteWrenchSpace |
A discrete 6D-wrench space used to describe the Grasp Wrench Space in ICR::Grasp. More... | |
class | Finger |
Holds a ICR::ContactPoint::id_ describing where on the target object the finger is centered as well as pointers to a list of patches, an ICR::OWS and a ICR::PointContactModel. More... | |
class | FingerParameters |
Describes contact force magnitude, friction cone discretization, friction coefficient, torsional friction coefficient, contact type, contact model type and the patch inclusion rule for a ICR::Finger. More... | |
class | Grasp |
The central class of the icrcpp library; Holds a list of ICR::Finger and a ICR::DiscreteWrenchSpace describing the Grasp Wrench Space. More... | |
struct | InclusionRule |
Describes a volume centered on a vertex of the target object; The id's of all vertices within this volume form a patch on the target object's surface. More... | |
class | IndependentContactRegions |
Holds shared pointers to the prototype ICR::Grasp and previously computed ICR::SearchZones; checks the contact points on the target object's surface for inclusion in the independent regions. More... | |
class | LimitSurface |
A disc parametrized by the contact force magnitude, the friction coefficient and the torsional friction coefficient according to "Howe, R.D and Cutkosky, M - Practical Force-Motion
Models for Sliding Manipulation; IJRR,1996". More... | |
class | MultiPointContactModel |
Derived from ICR::PointContactModel, has an additional member ICR::InclusionRule. More... | |
struct | Node |
A std::list<ICR::Node> acts as a FIFO list during the breadth-first computation of which points qualify for patch inclusion in ICR::Patch(uint centerpoint_id,TargetObject const& obj, InclusionRule const& rule) More... | |
class | ObjectLoader |
Loads object models provided in the Wavefront .obj format and builds a ICR::TargetObject. More... | |
class | OWS |
Holds a list of ICR::WrenchCone pointers describing the Object Wrench Space of the parent object. More... | |
struct | Patch |
Contains the id's of points forming a patch on the target object's surface in ICR::Patch::patch_ids_. More... | |
class | PointContactModel |
Base class for the ICR::MultiPointContactModel, holds a ICR::LimitSurface. More... | |
struct | PrimitiveSearchZone |
Used in ICR::IndependentContactRegions::primitiveSearchZoneInclusionTest to determine whether a contact point associated to a wrench cone is eligible for inclusion in the independent regions. More... | |
class | SearchZones |
Holds a std::vector of ICR::SearchZone pointers, one for each finger of the associated prototype grasp. More... | |
class | SphericalWrenchSpace |
A 6D-sphere used to describe a continous Task Wrench Space in ICR::SearchZones. More... | |
class | TargetObject |
Created by ICR::ObjectLoader; Holds the name of the loaded object and a ICR::ContactPointList describing the object. More... | |
class | WrenchCone |
Holds a matrix of prmimitve wrenches; The wrench cone id is the same as the id of the corresponding contact point. More... | |
class | WrenchSpace |
Base class from which ICR::SphericalWrenchSpace and ICR::DiscreteWrenchSpace are derived. More... | |
Typedefs | |
typedef Eigen::Array< uint, 1, 6 > | Array6ui |
typedef Eigen::Array< uint, Eigen::Dynamic, 6 > | ArrayX6ui |
typedef std::list< uint > ::const_iterator | ConstIndexListIterator |
typedef std::vector < ContactPoint * > | ContactPointList |
typedef std::vector< Patch * > | ContactRegion |
typedef std::vector < std::tr1::shared_ptr< Finger > > | FingerPtrList |
typedef std::vector < FingerParameters > | FParamList |
typedef std::tr1::shared_ptr < Grasp > | GraspPtr |
typedef std::tr1::shared_ptr < IndependentContactRegions > | IndependentContactRegionsPtr |
typedef std::list< uint > | IndexList |
typedef std::list< uint >::iterator | IndexListIterator |
typedef Eigen::Matrix< double, 6, Eigen::Dynamic > | Matrix6Xd |
typedef Eigen::Matrix< uint, Eigen::Dynamic, 6 > | MatrixX6ui |
typedef std::tr1::shared_ptr< OWS > | OWSPtr |
typedef std::tr1::shared_ptr < std::vector< Patch * > > | PatchListPtr |
typedef Eigen::Matrix< uint, 1, Eigen::Dynamic > | RowVectorXui |
typedef std::vector < PrimitiveSearchZone * > | SearchZone |
typedef std::tr1::shared_ptr < SearchZones > | SearchZonesPtr |
typedef std::tr1::shared_ptr < TargetObject > | TargetObjectPtr |
typedef unsigned int | uint |
typedef Eigen::Matrix< double, 6, 1 > | Vector6d |
typedef Eigen::Matrix< uint, Eigen::Dynamic, 1 > | VectorXui |
typedef std::vector< WrenchCone * > | WrenchConeList |
Enumerations | |
enum | ContactType { Undefined_CT = 1, Frictionless, Frictional, Soft_Finger } |
enum | ModelType { Undefined_MT = 1, Single_Point, Multi_Point } |
enum | RuleType { Undefined_RT = 1, Sphere } |
enum | WrenchSpaceType { Undefined_WS = 1, Discrete, Spherical } |
Functions | |
uint | dfactorial (uint x) |
uint | factorial (uint x) |
std::ostream & | operator<< (std::ostream &stream, PrimitiveSearchZone const &psz) |
std::ostream & | operator<< (std::ostream &stream, WrenchCone const &wrench_cone) |
std::ostream & | operator<< (std::ostream &stream, TargetObject const &obj) |
std::ostream & | operator<< (std::ostream &stream, ObjectLoader const &obj_loader) |
std::ostream & | operator<< (std::ostream &stream, Grasp const &grasp) |
std::ostream & | operator<< (std::ostream &stream, OWS const &ows) |
std::ostream & | operator<< (std::ostream &stream, ContactPoint const &cp) |
std::ostream & | operator<< (std::ostream &stream, InclusionRule const &inclusion_rule) |
std::ostream & | operator<< (std::ostream &stream, IndependentContactRegions const &icr) |
std::ostream & | operator<< (std::ostream &stream, SearchZones const &sz) |
std::ostream & | operator<< (std::ostream &stream, Node const &node) |
std::ostream & | operator<< (std::ostream &stream, PointContactModel const &pc_model) |
std::ostream & | operator<< (std::ostream &stream, SphericalWrenchSpace const &s_wrench_space) |
std::ostream & | operator<< (std::ostream &stream, LimitSurface const &lim_surf) |
std::ostream & | operator<< (std::ostream &stream, Patch const &patch) |
std::ostream & | operator<< (std::ostream &stream, DiscreteWrenchSpace const &d_wrench_space) |
std::ostream & | operator<< (std::ostream &stream, FingerParameters const ¶m) |
std::ostream & | operator<< (std::ostream &stream, Finger const &finger) |
Eigen::Matrix3d | skewSymmetricMatrix (Eigen::Vector3d vector) |
Variables | |
TargetObject * | callback_obj_ptr = NULL |
bool | face_callback_run = false |
Eigen::VectorXi | map_normal2vertex |
std::vector< double * > | normals_buffer |
std::vector< double * > | points_buffer |
typedef Eigen::Array<uint,1,6> ICR::Array6ui |
Definition at line 57 of file include/utilities.h.
typedef Eigen::Array<uint,Eigen::Dynamic,6> ICR::ArrayX6ui |
Definition at line 56 of file include/utilities.h.
typedef std::list<uint>::const_iterator ICR::ConstIndexListIterator |
Definition at line 61 of file include/utilities.h.
typedef std::vector<ContactPoint*> ICR::ContactPointList |
Definition at line 62 of file include/utilities.h.
typedef std::vector<Patch*> ICR::ContactRegion |
Definition at line 66 of file include/utilities.h.
typedef std::vector<std::tr1::shared_ptr<Finger> > ICR::FingerPtrList |
Definition at line 72 of file include/utilities.h.
typedef std::vector<FingerParameters> ICR::FParamList |
Definition at line 65 of file include/utilities.h.
typedef std::tr1::shared_ptr<Grasp> ICR::GraspPtr |
Definition at line 68 of file include/utilities.h.
typedef std::tr1::shared_ptr<IndependentContactRegions> ICR::IndependentContactRegionsPtr |
Definition at line 73 of file include/utilities.h.
typedef std::list<uint> ICR::IndexList |
Definition at line 59 of file include/utilities.h.
typedef std::list<uint>::iterator ICR::IndexListIterator |
Definition at line 60 of file include/utilities.h.
typedef Eigen::Matrix<double,6,Eigen::Dynamic> ICR::Matrix6Xd |
Definition at line 52 of file include/utilities.h.
typedef Eigen::Matrix<uint,Eigen::Dynamic,6> ICR::MatrixX6ui |
Definition at line 55 of file include/utilities.h.
typedef std::tr1::shared_ptr<OWS> ICR::OWSPtr |
Definition at line 70 of file include/utilities.h.
typedef std::tr1::shared_ptr<std::vector<Patch*> > ICR::PatchListPtr |
Definition at line 71 of file include/utilities.h.
typedef Eigen::Matrix<uint,1, Eigen::Dynamic > ICR::RowVectorXui |
Definition at line 53 of file include/utilities.h.
typedef std::vector<PrimitiveSearchZone*> ICR::SearchZone |
Definition at line 64 of file include/utilities.h.
typedef std::tr1::shared_ptr<SearchZones> ICR::SearchZonesPtr |
Definition at line 69 of file include/utilities.h.
typedef std::tr1::shared_ptr<TargetObject> ICR::TargetObjectPtr |
Definition at line 67 of file include/utilities.h.
typedef unsigned int ICR::uint |
Definition at line 51 of file include/utilities.h.
typedef Eigen::Matrix<double,6,1> ICR::Vector6d |
Definition at line 54 of file include/utilities.h.
typedef Eigen::Matrix<uint,Eigen::Dynamic,1> ICR::VectorXui |
Definition at line 58 of file include/utilities.h.
typedef std::vector<WrenchCone* > ICR::WrenchConeList |
Definition at line 63 of file include/utilities.h.
enum ICR::ContactType |
Definition at line 46 of file include/utilities.h.
enum ICR::ModelType |
Definition at line 47 of file include/utilities.h.
enum ICR::RuleType |
Definition at line 48 of file include/utilities.h.
enum ICR::WrenchSpaceType |
Definition at line 49 of file include/utilities.h.
uint ICR::dfactorial | ( | uint | x | ) |
Definition at line 25 of file utilities.cpp.
uint ICR::factorial | ( | uint | x | ) |
Definition at line 19 of file utilities.cpp.
std::ostream& ICR::operator<< | ( | std::ostream & | stream, |
PrimitiveSearchZone const & | psz | ||
) |
Definition at line 12 of file search_zones.cpp.
std::ostream& ICR::operator<< | ( | std::ostream & | stream, |
WrenchCone const & | wrench_cone | ||
) |
Definition at line 27 of file wrench_cone.cpp.
std::ostream& ICR::operator<< | ( | std::ostream & | stream, |
TargetObject const & | obj | ||
) |
Definition at line 28 of file target_object.cpp.
std::ostream& ICR::operator<< | ( | std::ostream & | stream, |
ObjectLoader const & | obj_loader | ||
) |
Definition at line 29 of file object_loader.cpp.
std::ostream& ICR::operator<< | ( | std::ostream & | stream, |
Grasp const & | grasp | ||
) |
std::ostream& ICR::operator<< | ( | std::ostream & | stream, |
OWS const & | ows | ||
) |
std::ostream& ICR::operator<< | ( | std::ostream & | stream, |
ContactPoint const & | cp | ||
) |
Definition at line 48 of file contact_point.cpp.
std::ostream& ICR::operator<< | ( | std::ostream & | stream, |
InclusionRule const & | inclusion_rule | ||
) |
Definition at line 49 of file finger.cpp.
std::ostream& ICR::operator<< | ( | std::ostream & | stream, |
IndependentContactRegions const & | icr | ||
) |
Definition at line 53 of file independent_contact_regions.cpp.
std::ostream& ICR::operator<< | ( | std::ostream & | stream, |
SearchZones const & | sz | ||
) |
Definition at line 57 of file search_zones.cpp.
std::ostream& ICR::operator<< | ( | std::ostream & | stream, |
Node const & | node | ||
) |
Definition at line 70 of file finger.cpp.
std::ostream& ICR::operator<< | ( | std::ostream & | stream, |
PointContactModel const & | pc_model | ||
) |
Definition at line 75 of file contact_model.cpp.
std::ostream& ICR::operator<< | ( | std::ostream & | stream, |
SphericalWrenchSpace const & | s_wrench_space | ||
) |
Definition at line 83 of file wrench_space.cpp.
std::ostream& ICR::operator<< | ( | std::ostream & | stream, |
LimitSurface const & | lim_surf | ||
) |
Definition at line 140 of file limit_surface.cpp.
std::ostream& ICR::operator<< | ( | std::ostream & | stream, |
Patch const & | patch | ||
) |
Definition at line 143 of file finger.cpp.
std::ostream& ICR::operator<< | ( | std::ostream & | stream, |
DiscreteWrenchSpace const & | d_wrench_space | ||
) |
Definition at line 165 of file wrench_space.cpp.
std::ostream& ICR::operator<< | ( | std::ostream & | stream, |
FingerParameters const & | param | ||
) |
Definition at line 242 of file finger.cpp.
std::ostream& ICR::operator<< | ( | std::ostream & | stream, |
Finger const & | finger | ||
) |
Definition at line 427 of file finger.cpp.
Eigen::Matrix3d ICR::skewSymmetricMatrix | ( | Eigen::Vector3d | vector | ) |
Definition at line 8 of file utilities.cpp.
TargetObject * ICR::callback_obj_ptr = NULL |
Definition at line 10 of file object_loader.cpp.
bool ICR::face_callback_run = false |
Definition at line 11 of file object_loader.cpp.
Eigen::VectorXi ICR::map_normal2vertex |
Definition at line 12 of file object_loader.cpp.
std::vector< double * > ICR::normals_buffer |
Definition at line 9 of file object_loader.cpp.
std::vector< double * > ICR::points_buffer |
Definition at line 8 of file object_loader.cpp.