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

Data Structures

struct  VolumeInfo
 
struct  WorkspaceCut2D
 
struct  WorkspaceCut2DTransformation
 

Public Types

enum  eOrientationType { RPY, EulerXYZ, EulerXYZExtrinsic, Hopf }
 
typedef int32_t ioIntTypeRead
 
typedef std::shared_ptr< WorkspaceCut2DWorkspaceCut2DPtr
 
typedef std::shared_ptr< WorkspaceCut2DTransformationWorkspaceCut2DTransformationPtr
 

Public Member Functions

 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)
 
virtual WorkspaceRepresentationPtr clone ()
 
WorkspaceDataPtr getData ()
 
bool getPoseFromVoxel (unsigned int x[], float v[]) const
 
virtual VolumeInfo computeVolumeInformation ()
 

Data Fields

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef int32_t ioIntTypeWrite
 

Protected Member Functions

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

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

Friends

class CoinVisualizationFactory
 

Detailed Description

This class represents a voxelized approximation of the workspace that is covered by a kinematic chain of a robot. The voxel grid covers the 6d Cartesian space: xyz translations (mm) and Tait-Bryan angles (eulerXYZ, fixed frame, extrinsic) orientations. Older versions (<=2.5) used RPY (intrinsic) for storing orientations, but it turned out that this representation is not suitable for discretization. Each voxels holds a counter (uchar) that holds information, e.g. about reachability. The discretized data can be written to and loaded from binary files.

The data 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 workspace representation is linked to the shoulder. When the torso moves, the data representation also changes it's position according to the position of the shoulder.

Member Typedef Documentation

◆ ioIntTypeRead

◆ WorkspaceCut2DPtr

◆ WorkspaceCut2DTransformationPtr

Member Enumeration Documentation

◆ eOrientationType

Enumerator
RPY 
EulerXYZ 
EulerXYZExtrinsic 
Hopf 

Constructor & Destructor Documentation

◆ WorkspaceRepresentation()

VirtualRobot::WorkspaceRepresentation::WorkspaceRepresentation ( RobotPtr  robot)

Member Function Documentation

◆ addCurrentTCPPose()

void VirtualRobot::WorkspaceRepresentation::addCurrentTCPPose ( )
virtual

Compute the quality of the current pose and add entry to voxel data (if is larger than the existing entry).

◆ addPose() [1/2]

void VirtualRobot::WorkspaceRepresentation::addPose ( const Eigen::Matrix4f &  globalPose)
virtual

◆ addPose() [2/2]

void VirtualRobot::WorkspaceRepresentation::addPose ( const Eigen::Matrix4f &  p,
PoseQualityMeasurementPtr  qualMeasure 
)
virtual

addPose Adds pose and rate it with the given quality measure. Ignored in this implementation, but used in derived classes (

See also
Manipulability)
Parameters
p
qualMeasure

Reimplemented in VirtualRobot::Manipulability.

◆ addRandomTCPPoses() [1/2]

void VirtualRobot::WorkspaceRepresentation::addRandomTCPPoses ( unsigned int  loops,
bool  checkForSelfCollisions = true 
)

Append a number of random TCP poses to workspace Data. For bigger sampling rates (loops > 50.000) you should consider this method's multithreaded pendant.

Parameters
loopsNumber of poses that should be appended
checkForSelfCollisionsBuild a collision-free configuration. If true, random configs are generated until one is collision-free.

◆ addRandomTCPPoses() [2/2]

void VirtualRobot::WorkspaceRepresentation::addRandomTCPPoses ( unsigned int  loops,
unsigned int  numThreads,
bool  checkForSelfCollisions = true 
)
virtual

Appends a number of random TCP poses to workspace Data (multithreaded). This method is blocking, i.e. it returns as soon as all threads are done.

Parameters
loopsNumber of poses that should be appended
numThreadsnumber of worker threads used behind the scenes to append random TCP poses to workspace data.
checkForSelfCollisionsBuild a collision-free configuration. If true, random configs are generated until one is collision-free.

Reimplemented in VirtualRobot::Manipulability.

◆ avgAngleReachabilities()

int VirtualRobot::WorkspaceRepresentation::avgAngleReachabilities ( int  x0,
int  x1,
int  x2 
) const
virtual

◆ binarize()

void VirtualRobot::WorkspaceRepresentation::binarize ( )
virtual

Cut all data >1 to 1. This reduces the file size when saving compressed data.

◆ checkForParameters()

bool VirtualRobot::WorkspaceRepresentation::checkForParameters ( RobotNodeSetPtr  nodeSet,
float  steps,
float  storeMinBounds[6],
float  storeMaxBounds[6],
RobotNodePtr  baseNode = RobotNodePtr(),
RobotNodePtr  tcpNode = RobotNodePtr() 
)
virtual

Estimate a parameter setup for the given RNS by randomly set configurations and check for achieved workspace extends. The results are slightly scaled.

Parameters
ndoeSet
stepsHow many loops should be performed to estimate the result. Chose a value >= 1000.
storeMinBoundsWorkspace extend from min
storeMaxBoundsWorkspace extend to max
baseNode
tcpNode
Returns
True on success.

◆ clear()

void VirtualRobot::WorkspaceRepresentation::clear ( )
virtual

Clears all data

◆ clone()

VirtualRobot::WorkspaceRepresentationPtr VirtualRobot::WorkspaceRepresentation::clone ( )
virtual

Creates a deep copy of this data structure. Derived classes may overwrite this method that provides a generic interface for cloning.

Reimplemented in VirtualRobot::Manipulability, and VirtualRobot::Reachability.

◆ compressData()

unsigned char * VirtualRobot::WorkspaceRepresentation::compressData ( const unsigned char *  source,
int  size,
int &  compressedSize 
)
protected

Compress the data.

◆ computeVolumeInformation()

WorkspaceRepresentation::VolumeInfo VirtualRobot::WorkspaceRepresentation::computeVolumeInformation ( )
virtual

◆ createCut() [1/2]

WorkspaceRepresentation::WorkspaceCut2DPtr VirtualRobot::WorkspaceRepresentation::createCut ( const Eigen::Matrix4f &  referencePose,
float  cellSize,
bool  sumAngles 
) const

Create a horizontal cut through this workspace data. Therefore, the z component and the orientation of the reference pose (in global coordinate system) is used. Then the x and y components are iterated and the corresponding entires are used to fill the 2d grid.

◆ createCut() [2/2]

WorkspaceRepresentation::WorkspaceCut2DPtr VirtualRobot::WorkspaceRepresentation::createCut ( float  heightPercent,
float  cellSize,
bool  sumAngles 
) const

createCut Create a cut at a specific height (assuming z is upwards).

Parameters
heightPercentValue in [0,1]
cellSizeThe discretization step size of the result
Returns

◆ createCutTransformations()

std::vector< WorkspaceRepresentation::WorkspaceCut2DTransformationPtr > VirtualRobot::WorkspaceRepresentation::createCutTransformations ( WorkspaceRepresentation::WorkspaceCut2DPtr  cutXY,
RobotNodePtr  referenceNode = RobotNodePtr(),
float  maxAngle = M_PIf32 
)

Build all transformations from referenceNode to cutXY data.h Only entries>0 are considered. If referenceNode is set, the transformations are given in the corresponding coordinate system.

◆ customInitialize()

virtual void VirtualRobot::WorkspaceRepresentation::customInitialize ( )
inlineprotectedvirtual

◆ customLoad()

virtual bool VirtualRobot::WorkspaceRepresentation::customLoad ( std::ifstream &  )
inlineprotectedvirtual

Derived classes may implement some custom data access.

Reimplemented in VirtualRobot::Manipulability.

◆ customPrint()

virtual void VirtualRobot::WorkspaceRepresentation::customPrint ( )
inlineprotectedvirtual

Reimplemented in VirtualRobot::Manipulability.

◆ customSave()

virtual bool VirtualRobot::WorkspaceRepresentation::customSave ( std::ofstream &  )
inlineprotectedvirtual

Derived classes may implement some custom data access.

Reimplemented in VirtualRobot::Manipulability.

◆ fillHoles()

int VirtualRobot::WorkspaceRepresentation::fillHoles ( unsigned int  minNeighbors = 1)
virtual

Checks for all voxels with entry==0 if there are neighbors with entries>0. If so the entry is set to the averaged value of the neighbors

Parameters
minNeighborsThe minimum number of neighbors that have to have an entry>0
Returns
The number of changed voxels.

◆ getAdjustOnOverflow()

bool VirtualRobot::WorkspaceRepresentation::getAdjustOnOverflow ( )
inline

◆ getBaseNode()

RobotNodePtr VirtualRobot::WorkspaceRepresentation::getBaseNode ( )

The base node of this workspace data.

◆ getCollisionModelDynamic()

SceneObjectSetPtr VirtualRobot::WorkspaceRepresentation::getCollisionModelDynamic ( )
inline

◆ getCollisionModelStatic()

SceneObjectSetPtr VirtualRobot::WorkspaceRepresentation::getCollisionModelStatic ( )
inline

◆ getData()

VirtualRobot::WorkspaceDataPtr VirtualRobot::WorkspaceRepresentation::getData ( )

Returns the raw data.

◆ getDiscretizeParameterRotation()

float VirtualRobot::WorkspaceRepresentation::getDiscretizeParameterRotation ( )

◆ getDiscretizeParameterTranslation()

float VirtualRobot::WorkspaceRepresentation::getDiscretizeParameterTranslation ( )

◆ getEntry()

unsigned char VirtualRobot::WorkspaceRepresentation::getEntry ( const Eigen::Matrix4f &  globalPose) const

Return corresponding entry of workspace data

◆ getMaxBound()

float VirtualRobot::WorkspaceRepresentation::getMaxBound ( int  dim) const
virtual

◆ getMaxEntry() [1/3]

int VirtualRobot::WorkspaceRepresentation::getMaxEntry ( ) const

Returns the maximum entry of a voxel.

◆ getMaxEntry() [2/3]

int VirtualRobot::WorkspaceRepresentation::getMaxEntry ( int  x0,
int  x1,
int  x2 
) const
virtual

Searches all angle entries (x3,x4,x5) for maximum entry. (x0,x1,x2) is the voxel position.

◆ getMaxEntry() [3/3]

int VirtualRobot::WorkspaceRepresentation::getMaxEntry ( const Eigen::Vector3f &  position_global) const
virtual

Returns the maximum workspace entry that can be achieved by an arbitrary orientation at the given position.

◆ getMaxSummedAngleReachablity()

int VirtualRobot::WorkspaceRepresentation::getMaxSummedAngleReachablity ( )
virtual

Returns the maximum that can be achieved by calling sumAngleReachabilities()

◆ getMinBound()

float VirtualRobot::WorkspaceRepresentation::getMinBound ( int  dim) const
virtual

◆ getNodeSet()

RobotNodeSetPtr VirtualRobot::WorkspaceRepresentation::getNodeSet ( )

The kinematic chain that is covered by this workspace data.

◆ getNumVoxels()

int VirtualRobot::WorkspaceRepresentation::getNumVoxels ( int  dim) const
virtual

◆ getOOBB()

MathTools::OOBB VirtualRobot::WorkspaceRepresentation::getOOBB ( bool  achievedValues = false) const

The bounding box in global frame.

Parameters
achievedValuesIf not set the bounding box as defined on construction is returned. If set the min/max achieved positions are used.
Returns
The object oriented bounding box

◆ getPoseFromVoxel() [1/3]

Eigen::Matrix4f VirtualRobot::WorkspaceRepresentation::getPoseFromVoxel ( unsigned int  v[6],
bool  transformToGlobalPose = true 
)

Computes center of corresponding voxel in global coord system.

◆ getPoseFromVoxel() [2/3]

Eigen::Matrix4f VirtualRobot::WorkspaceRepresentation::getPoseFromVoxel ( float  v[6],
bool  transformToGlobalPose = true 
)

◆ getPoseFromVoxel() [3/3]

bool VirtualRobot::WorkspaceRepresentation::getPoseFromVoxel ( unsigned int  x[],
float  v[] 
) const

◆ getRobot()

RobotPtr VirtualRobot::WorkspaceRepresentation::getRobot ( )
inline

◆ getTCP()

RobotNodePtr VirtualRobot::WorkspaceRepresentation::getTCP ( )

The corresponding TCP.

◆ getTcp()

RobotNodePtr VirtualRobot::WorkspaceRepresentation::getTcp ( )
inline

◆ getToGlobalTransformation()

Eigen::Matrix4f VirtualRobot::WorkspaceRepresentation::getToGlobalTransformation ( ) const
protectedvirtual

◆ getToLocalTransformation()

Eigen::Matrix4f VirtualRobot::WorkspaceRepresentation::getToLocalTransformation ( ) const
protectedvirtual

◆ getVoxelEntry()

unsigned char VirtualRobot::WorkspaceRepresentation::getVoxelEntry ( unsigned int  a,
unsigned int  b,
unsigned int  c,
unsigned int  d,
unsigned int  e,
unsigned int  f 
) const
virtual

get entry of given voxel.

◆ getVoxelFromPose() [1/2]

bool VirtualRobot::WorkspaceRepresentation::getVoxelFromPose ( const Eigen::Matrix4f &  globalPose,
unsigned int  v[6] 
) const
virtual

Get the corresponding voxel. If false is returned the pose is outside the covered workspace.

◆ getVoxelFromPose() [2/2]

bool VirtualRobot::WorkspaceRepresentation::getVoxelFromPose ( float  x[6],
unsigned int  v[6] 
) const
virtual

◆ getVoxelFromPosition() [1/2]

bool VirtualRobot::WorkspaceRepresentation::getVoxelFromPosition ( const Eigen::Matrix4f &  globalPose,
unsigned int  v[3] 
) const
virtual

Get the corresponding voxel coordinates. If false is returned the position is outside the covered workspace.

◆ getVoxelFromPosition() [2/2]

bool VirtualRobot::WorkspaceRepresentation::getVoxelFromPosition ( float  x[3],
unsigned int  v[3] 
) const
virtual

◆ getVoxelSize()

float VirtualRobot::WorkspaceRepresentation::getVoxelSize ( int  dim) const

returns the extends of a voxel at corresponding dimension.

◆ getWorkspaceExtends()

bool VirtualRobot::WorkspaceRepresentation::getWorkspaceExtends ( Eigen::Vector3f &  storeMinBBox,
Eigen::Vector3f &  storeMaxBBox 
) const

Computes the axis aligned bounding box of this object in global coordinate system. Note, that the bbox changes when the robot moves.

◆ hasEntry()

bool VirtualRobot::WorkspaceRepresentation::hasEntry ( unsigned int  x,
unsigned int  y,
unsigned int  z 
)
virtual

Returns true if for the given 3d position is at least one entry >0

Parameters
xVoxel position x0
yVoxel position x1
zVoxel position x2

◆ initialize()

void VirtualRobot::WorkspaceRepresentation::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

Initialize and reset all data.

Parameters
nodeSetThe robot node set that should be considered for workspace (e.g. reachability) analysis.
discretizeStepTranslationThe extend of a voxel dimension in translational dimensions (x,y,z) [mm]
discretizeStepRotationThe extend of a voxel dimension in rotational dimensions (roll, pitch, yaw) [rad]
minBoundsThe minimum workspace poses (x,y,z,ro,pi,ya) given in baseNode's coordinate system [mm and rad]
maxBoundsThe maximum workspace poses (x,y,z,ro,pi,ya) given in baseNode's coordinate system [mm and rad]
staticCollisionModelThe static collision model of the robot. This model does not move when changing the configuration of the RobotNodeSet. If not set no collisions will be checked when building the reachability data
dynamicCollisionModelThe dynamic collision model of the robot. This model does move when changing the configuration of the RobotNodeSet. If not set no collisions will be checked when building the reachability data.
baseNodePerform the computations in the coordinate system of this node. If not set, the global pose is used (be careful, when the robot moves around global poses may not be meaningful!)
tcpNodeIf given, the pose of this node is used for workspace calculations. If not given, the TCP node of the nodeSet is used.
adjustOnOverflowIf set, the 8bit data is divided by 2 when one voxel entry exceeds 255. Otherwise the entries remain at 255.

◆ invalidateBehindRobot()

void VirtualRobot::WorkspaceRepresentation::invalidateBehindRobot ( bool  inverted = false)

◆ isCovered() [1/2]

bool VirtualRobot::WorkspaceRepresentation::isCovered ( const Eigen::Matrix4f &  globalPose)

Returns true, if the corresponding voxel entry is not zero.

◆ isCovered() [2/2]

bool VirtualRobot::WorkspaceRepresentation::isCovered ( unsigned int  v[6])

Returns true, if voxel entry is not zero.

◆ load()

void VirtualRobot::WorkspaceRepresentation::load ( const std::string &  filename)
virtual

Load the workspace data from a binary file. Exceptions are thrown on case errors are detected.

◆ matrix2Vector()

void VirtualRobot::WorkspaceRepresentation::matrix2Vector ( const Eigen::Matrix4f &  m,
float  x[6] 
) const

Convert a 4x4 matrix to a pos + ori vector.

◆ print()

void VirtualRobot::WorkspaceRepresentation::print ( )
virtual

Print status information

◆ reset()

void VirtualRobot::WorkspaceRepresentation::reset ( )
virtual

Reset all data.

◆ sampleCoveredPose()

Eigen::Matrix4f VirtualRobot::WorkspaceRepresentation::sampleCoveredPose ( )

returns a random pose that is covered by the workspace data

◆ save()

void VirtualRobot::WorkspaceRepresentation::save ( const std::string &  filename)
virtual

Store the workspace data to a binary file. Exceptions are thrown on case errors are detected.

◆ setCurrentTCPPoseEntry()

void VirtualRobot::WorkspaceRepresentation::setCurrentTCPPoseEntry ( unsigned char  e)
virtual

Sets entry that corresponds to TCP pose to e. Therefore the corresponding voxel of the current TCP pose is determined and its entry is set.

◆ setCurrentTCPPoseEntryIfLower()

void VirtualRobot::WorkspaceRepresentation::setCurrentTCPPoseEntryIfLower ( unsigned char  e)
virtual

Sets entry that corresponds to TCP pose to e, if current entry is lower than e. Therefore the corresponding voxel of the current TCP pose is determined and its entry is adjusted.

◆ setEntry()

void VirtualRobot::WorkspaceRepresentation::setEntry ( const Eigen::Matrix4f &  poseGlobal,
unsigned char  e 
)

◆ setEntryCheckNeighbors()

void VirtualRobot::WorkspaceRepresentation::setEntryCheckNeighbors ( const Eigen::Matrix4f &  poseGlobal,
unsigned char  e,
unsigned int  neighborVoxels 
)

◆ setOrientationType()

void VirtualRobot::WorkspaceRepresentation::setOrientationType ( eOrientationType  t)

Usually not needed. Don't call this method after data has been loaded or created!

◆ setRobotNodesToRandomConfig()

bool VirtualRobot::WorkspaceRepresentation::setRobotNodesToRandomConfig ( VirtualRobot::RobotNodeSetPtr  nodeSet = VirtualRobot::RobotNodeSetPtr(),
bool  checkForSelfCollisions = true 
)
virtual

Generate a random configuration for the robot node set. This configuration is within the joint limits of the current robot node set.

Parameters
nodeSetThe nodes. If not given, the standard nodeSet is used.
checkForSelfCollisionsBuild a collision-free configuration. If true, random configs are generated until one is collision-free.

◆ setVoxelEntry()

void VirtualRobot::WorkspaceRepresentation::setVoxelEntry ( unsigned int  v[6],
unsigned char  e 
)

◆ sumAngleReachabilities()

int VirtualRobot::WorkspaceRepresentation::sumAngleReachabilities ( int  x0,
int  x1,
int  x2 
) const
virtual

Sums all angle (x3,x4,x5) entries for the given position.

◆ toGlobal()

void VirtualRobot::WorkspaceRepresentation::toGlobal ( Eigen::Matrix4f &  p) const
virtual

◆ toGlobalVec()

void VirtualRobot::WorkspaceRepresentation::toGlobalVec ( Eigen::Vector3f &  positionLocal) const

◆ toLocal()

void VirtualRobot::WorkspaceRepresentation::toLocal ( Eigen::Matrix4f &  p) const
virtual

◆ toLocalVec()

void VirtualRobot::WorkspaceRepresentation::toLocalVec ( Eigen::Vector3f &  positionGlobal) const

◆ uncompressData()

void VirtualRobot::WorkspaceRepresentation::uncompressData ( const unsigned char *  source,
int  size,
unsigned char *  dest 
)
protected

Uncompress the data.

◆ vector2Matrix() [1/2]

void VirtualRobot::WorkspaceRepresentation::vector2Matrix ( const float  x[6],
Eigen::Matrix4f &  m 
) const

◆ vector2Matrix() [2/2]

void VirtualRobot::WorkspaceRepresentation::vector2Matrix ( const Eigen::Vector3f &  pos,
const Eigen::Vector3f &  rot,
Eigen::Matrix4f &  m 
) const

Friends And Related Function Documentation

◆ CoinVisualizationFactory

friend class CoinVisualizationFactory
friend

Field Documentation

◆ achievedMaxValues

float VirtualRobot::WorkspaceRepresentation::achievedMaxValues[6]
protected

◆ achievedMinValues

float VirtualRobot::WorkspaceRepresentation::achievedMinValues[6]
protected

◆ adjustOnOverflow

bool VirtualRobot::WorkspaceRepresentation::adjustOnOverflow
protected

◆ baseNode

RobotNodePtr VirtualRobot::WorkspaceRepresentation::baseNode
protected

◆ buildUpLoops

int VirtualRobot::WorkspaceRepresentation::buildUpLoops
protected

◆ collisionConfigs

int VirtualRobot::WorkspaceRepresentation::collisionConfigs
protected

◆ data

WorkspaceDataPtr VirtualRobot::WorkspaceRepresentation::data
protected

◆ discretizeStepRotation

float VirtualRobot::WorkspaceRepresentation::discretizeStepRotation
protected

◆ discretizeStepTranslation

float VirtualRobot::WorkspaceRepresentation::discretizeStepTranslation
protected

◆ dynamicCollisionModel

SceneObjectSetPtr VirtualRobot::WorkspaceRepresentation::dynamicCollisionModel
protected

◆ ioIntTypeWrite

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef int32_t VirtualRobot::WorkspaceRepresentation::ioIntTypeWrite

◆ maxBounds

float VirtualRobot::WorkspaceRepresentation::maxBounds[6]
protected

◆ minBounds

float VirtualRobot::WorkspaceRepresentation::minBounds[6]
protected

◆ nodeSet

RobotNodeSetPtr VirtualRobot::WorkspaceRepresentation::nodeSet
protected

◆ numVoxels

int VirtualRobot::WorkspaceRepresentation::numVoxels[6]
protected

◆ orientationType

eOrientationType VirtualRobot::WorkspaceRepresentation::orientationType
protected

Specifies how the rotation part (x[3],x[4],x[5]) of an 6D voxel entry is encoded.

◆ robot

RobotPtr VirtualRobot::WorkspaceRepresentation::robot
protected

◆ spaceSize

float VirtualRobot::WorkspaceRepresentation::spaceSize[6]
protected

◆ staticCollisionModel

SceneObjectSetPtr VirtualRobot::WorkspaceRepresentation::staticCollisionModel
protected

◆ tcpNode

RobotNodePtr VirtualRobot::WorkspaceRepresentation::tcpNode
protected

◆ type

std::string VirtualRobot::WorkspaceRepresentation::type
protected

◆ versionMajor

int VirtualRobot::WorkspaceRepresentation::versionMajor
protected

◆ versionMinor

int VirtualRobot::WorkspaceRepresentation::versionMinor
protected