Simox  2.3.74.0
VirtualRobot::Reachability Class Reference
Inheritance diagram for VirtualRobot::Reachability:
VirtualRobot::WorkspaceRepresentation

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW Reachability (RobotPtr robot)
 
bool isReachable (const Eigen::Matrix4f &globalPose)
 
GraspSetPtr getReachableGrasps (GraspSetPtr grasps, ManipulationObjectPtr object)
 
Eigen::Matrix4f sampleReachablePose ()
 returns a random pose that is covered by the workspace data. More...
 
WorkspaceRepresentationPtr clone () override
 
- Public Member Functions inherited from VirtualRobot::WorkspaceRepresentation
 WorkspaceRepresentation (RobotPtr robot)
 
virtual void reset ()
 
virtual void load (const std::string &filename)
 
virtual void save (const std::string &filename)
 
unsigned char getEntry (const Eigen::Matrix4f &globalPose) const
 
int getMaxEntry () const
 Returns the maximum entry of a voxel. More...
 
float getVoxelSize (int dim) const
 returns the extends of a voxel at corresponding dimension. More...
 
RobotNodePtr getBaseNode ()
 The base node of this workspace data. More...
 
RobotNodePtr getTCP ()
 The corresponding TCP. More...
 
RobotNodeSetPtr getNodeSet ()
 The kinematic chain that is covered by this workspace data. More...
 
void invalidateBehindRobot (bool inverted=false)
 
virtual void initialize (RobotNodeSetPtr nodeSet, float discretizeStepTranslation, float discretizeStepRotation, const float minBounds[6], const float maxBounds[6], SceneObjectSetPtr staticCollisionModel=SceneObjectSetPtr(), SceneObjectSetPtr dynamicCollisionModel=SceneObjectSetPtr(), RobotNodePtr baseNode=RobotNodePtr(), RobotNodePtr tcpNode=RobotNodePtr(), bool adjustOnOverflow=true)
 
virtual void setCurrentTCPPoseEntryIfLower (unsigned char e)
 
virtual void setCurrentTCPPoseEntry (unsigned char e)
 
virtual void addPose (const Eigen::Matrix4f &globalPose)
 
virtual void addPose (const Eigen::Matrix4f &p, PoseQualityMeasurementPtr qualMeasure)
 addPose Adds pose and rate it with the given quality measure. Ignored in this implementation, but used in derived classes ( More...
 
virtual void clear ()
 
virtual bool setRobotNodesToRandomConfig (VirtualRobot::RobotNodeSetPtr nodeSet=VirtualRobot::RobotNodeSetPtr(), bool checkForSelfCollisions=true)
 
virtual void binarize ()
 
virtual int fillHoles (unsigned int minNeighbors=1)
 
virtual void print ()
 
Eigen::Matrix4f sampleCoveredPose ()
 returns a random pose that is covered by the workspace data More...
 
bool isCovered (const Eigen::Matrix4f &globalPose)
 
bool isCovered (unsigned int v[6])
 
virtual int getNumVoxels (int dim) const
 
virtual float getMinBound (int dim) const
 
virtual float getMaxBound (int dim) const
 
virtual unsigned char getVoxelEntry (unsigned int a, unsigned int b, unsigned int c, unsigned int d, unsigned int e, unsigned int f) const
 
virtual int sumAngleReachabilities (int x0, int x1, int x2) const
 
virtual int avgAngleReachabilities (int x0, int x1, int x2) const
 
virtual int getMaxEntry (int x0, int x1, int x2) const
 
virtual int getMaxEntry (const Eigen::Vector3f &position_global) const
 
virtual bool getVoxelFromPose (const Eigen::Matrix4f &globalPose, unsigned int v[6]) const
 
virtual bool getVoxelFromPosition (const Eigen::Matrix4f &globalPose, unsigned int v[3]) const
 
Eigen::Matrix4f getPoseFromVoxel (unsigned int v[6], bool transformToGlobalPose=true)
 
Eigen::Matrix4f getPoseFromVoxel (float v[6], bool transformToGlobalPose=true)
 
virtual int getMaxSummedAngleReachablity ()
 
virtual bool hasEntry (unsigned int x, unsigned int y, unsigned int z)
 
virtual bool checkForParameters (RobotNodeSetPtr nodeSet, float steps, float storeMinBounds[6], float storeMaxBounds[6], RobotNodePtr baseNode=RobotNodePtr(), RobotNodePtr tcpNode=RobotNodePtr())
 
WorkspaceCut2DPtr createCut (const Eigen::Matrix4f &referencePose, float cellSize, bool sumAngles) const
 
WorkspaceCut2DPtr createCut (float heightPercent, float cellSize, bool sumAngles) const
 createCut Create a cut at a specific height (assuming z is upwards). More...
 
std::vector< WorkspaceCut2DTransformationPtrcreateCutTransformations (WorkspaceCut2DPtr cutXY, RobotNodePtr referenceNode=RobotNodePtr(), float maxAngle=M_PIf32)
 
bool getWorkspaceExtends (Eigen::Vector3f &storeMinBBox, Eigen::Vector3f &storeMaxBBox) const
 
MathTools::OOBB getOOBB (bool achievedValues=false) const
 
float getDiscretizeParameterTranslation ()
 
float getDiscretizeParameterRotation ()
 
RobotPtr getRobot ()
 
SceneObjectSetPtr getCollisionModelStatic ()
 
SceneObjectSetPtr getCollisionModelDynamic ()
 
RobotNodePtr getTcp ()
 
bool getAdjustOnOverflow ()
 
virtual void addCurrentTCPPose ()
 
void addRandomTCPPoses (unsigned int loops, bool checkForSelfCollisions=true)
 
virtual void addRandomTCPPoses (unsigned int loops, unsigned int numThreads, bool checkForSelfCollisions=true)
 
void setVoxelEntry (unsigned int v[6], unsigned char e)
 
void setEntry (const Eigen::Matrix4f &poseGlobal, unsigned char e)
 
void setEntryCheckNeighbors (const Eigen::Matrix4f &poseGlobal, unsigned char e, unsigned int neighborVoxels)
 
virtual void toLocal (Eigen::Matrix4f &p) const
 
virtual void toGlobal (Eigen::Matrix4f &p) const
 
void toLocalVec (Eigen::Vector3f &positionGlobal) const
 
void toGlobalVec (Eigen::Vector3f &positionLocal) const
 
void matrix2Vector (const Eigen::Matrix4f &m, float x[6]) const
 Convert a 4x4 matrix to a pos + ori vector. More...
 
void vector2Matrix (const float x[6], Eigen::Matrix4f &m) const
 
void vector2Matrix (const Eigen::Vector3f &pos, const Eigen::Vector3f &rot, Eigen::Matrix4f &m) const
 
virtual bool getVoxelFromPose (float x[6], unsigned int v[6]) const
 
virtual bool getVoxelFromPosition (float x[3], unsigned int v[3]) const
 
void setOrientationType (eOrientationType t)
 
WorkspaceDataPtr getData ()
 
bool getPoseFromVoxel (unsigned int x[], float v[]) const
 
virtual VolumeInfo computeVolumeInformation ()
 

Friends

class CoinVisualizationFactory
 

Additional Inherited Members

- Public Types inherited from VirtualRobot::WorkspaceRepresentation
enum  eOrientationType { RPY, EulerXYZ, EulerXYZExtrinsic, Hopf }
 
typedef int32_t ioIntTypeRead
 
typedef std::shared_ptr< WorkspaceCut2DWorkspaceCut2DPtr
 
typedef std::shared_ptr< WorkspaceCut2DTransformationWorkspaceCut2DTransformationPtr
 
- Data Fields inherited from VirtualRobot::WorkspaceRepresentation
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef int32_t ioIntTypeWrite
 
- Protected Member Functions inherited from VirtualRobot::WorkspaceRepresentation
virtual bool customLoad (std::ifstream &)
 
virtual bool customSave (std::ofstream &)
 
virtual void customInitialize ()
 
virtual void customPrint ()
 
void uncompressData (const unsigned char *source, int size, unsigned char *dest)
 Uncompress the data. More...
 
unsigned char * compressData (const unsigned char *source, int size, int &compressedSize)
 Compress the data. More...
 
virtual Eigen::Matrix4f getToLocalTransformation () const
 
virtual Eigen::Matrix4f getToGlobalTransformation () const
 
- Protected Attributes inherited from VirtualRobot::WorkspaceRepresentation
RobotPtr robot
 
RobotNodePtr baseNode
 
RobotNodePtr tcpNode
 
RobotNodeSetPtr nodeSet
 
SceneObjectSetPtr staticCollisionModel
 
SceneObjectSetPtr dynamicCollisionModel
 
int buildUpLoops
 
int collisionConfigs
 
float discretizeStepTranslation
 
float discretizeStepRotation
 
float minBounds [6]
 
float maxBounds [6]
 
int numVoxels [6]
 
float achievedMinValues [6]
 
float achievedMaxValues [6]
 
float spaceSize [6]
 
WorkspaceDataPtr data
 
bool adjustOnOverflow
 
std::string type
 
int versionMajor
 
int versionMinor
 
eOrientationType orientationType
 Specifies how the rotation part (x[3],x[4],x[5]) of an 6D voxel entry is encoded. More...
 

Detailed Description

This class represents an approximation of the reachability distribution of a kinematic chain (e.g. an arm). Consists of voxels covering the 6D space for position (XYZ) and orientation (Tait–Bryan angles, EulerXYZ, static frame). Each voxel holds a counter with the number of successful IK solver calls, representing the approximated probability that an IK solver call can be successfully answered. The discretized reachability data can be written to and loaded from binary files.

The reachability is linked to a base coordinate system which is defined by a robot joint. This base system is used to align the data when the robot is moving. I.E. think of an arm of a humanoid where the reachability is linked to the shoulder. When the torso moves, the reachability also changes it's position according to the position of the shoulder.

Constructor & Destructor Documentation

◆ Reachability()

VirtualRobot::Reachability::Reachability ( RobotPtr  robot)

Member Function Documentation

◆ clone()

VirtualRobot::WorkspaceRepresentationPtr VirtualRobot::Reachability::clone ( )
overridevirtual

Creates a deep copy of this data structure. A ReachabilityPtr is returned.

Reimplemented from VirtualRobot::WorkspaceRepresentation.

◆ getReachableGrasps()

VirtualRobot::GraspSetPtr VirtualRobot::Reachability::getReachableGrasps ( GraspSetPtr  grasps,
ManipulationObjectPtr  object 
)

Returns all reachable grasps that can be applied at the current position of object.

◆ isReachable()

bool VirtualRobot::Reachability::isReachable ( const Eigen::Matrix4f &  globalPose)

Returns true, if the corresponding reachability entry is non zero.

◆ sampleReachablePose()

Eigen::Matrix4f VirtualRobot::Reachability::sampleReachablePose ( )

returns a random pose that is covered by the workspace data.

Friends And Related Function Documentation

◆ CoinVisualizationFactory

friend class CoinVisualizationFactory
friend