Simox
2.3.74.0
|
Data Structures | |
struct | VolumeInfo |
struct | WorkspaceCut2D |
struct | WorkspaceCut2DTransformation |
Public Types | |
enum | eOrientationType { RPY, EulerXYZ, EulerXYZExtrinsic, Hopf } |
typedef int32_t | ioIntTypeRead |
typedef std::shared_ptr< WorkspaceCut2D > | WorkspaceCut2DPtr |
typedef std::shared_ptr< WorkspaceCut2DTransformation > | WorkspaceCut2DTransformationPtr |
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< WorkspaceCut2DTransformationPtr > | createCutTransformations (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 |
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.
typedef int32_t VirtualRobot::WorkspaceRepresentation::ioIntTypeRead |
typedef std::shared_ptr<WorkspaceCut2D> VirtualRobot::WorkspaceRepresentation::WorkspaceCut2DPtr |
typedef std::shared_ptr<WorkspaceCut2DTransformation> VirtualRobot::WorkspaceRepresentation::WorkspaceCut2DTransformationPtr |
VirtualRobot::WorkspaceRepresentation::WorkspaceRepresentation | ( | RobotPtr | robot | ) |
|
virtual |
Compute the quality of the current pose and add entry to voxel data (if is larger than the existing entry).
|
virtual |
Reimplemented in VirtualRobot::Manipulability, and VirtualRobot::NaturalPosture.
|
virtual |
addPose Adds pose and rate it with the given quality measure. Ignored in this implementation, but used in derived classes (
p | |
qualMeasure |
Reimplemented in VirtualRobot::Manipulability.
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.
loops | Number of poses that should be appended |
checkForSelfCollisions | Build a collision-free configuration. If true, random configs are generated until one is collision-free. |
|
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.
loops | Number of poses that should be appended |
numThreads | number of worker threads used behind the scenes to append random TCP poses to workspace data. |
checkForSelfCollisions | Build a collision-free configuration. If true, random configs are generated until one is collision-free. |
Reimplemented in VirtualRobot::Manipulability.
|
virtual |
|
virtual |
Cut all data >1 to 1. This reduces the file size when saving compressed data.
|
virtual |
Estimate a parameter setup for the given RNS by randomly set configurations and check for achieved workspace extends. The results are slightly scaled.
ndoeSet | |
steps | How many loops should be performed to estimate the result. Chose a value >= 1000. |
storeMinBounds | Workspace extend from min |
storeMaxBounds | Workspace extend to max |
baseNode | |
tcpNode |
|
virtual |
Clears all data
|
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.
|
protected |
Compress the data.
|
virtual |
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.
WorkspaceRepresentation::WorkspaceCut2DPtr VirtualRobot::WorkspaceRepresentation::createCut | ( | float | heightPercent, |
float | cellSize, | ||
bool | sumAngles | ||
) | const |
createCut Create a cut at a specific height (assuming z is upwards).
heightPercent | Value in [0,1] |
cellSize | The discretization step size of the result |
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.
|
inlineprotectedvirtual |
Reimplemented in VirtualRobot::Manipulability, and VirtualRobot::NaturalPosture.
|
inlineprotectedvirtual |
Derived classes may implement some custom data access.
Reimplemented in VirtualRobot::Manipulability.
|
inlineprotectedvirtual |
Reimplemented in VirtualRobot::Manipulability.
|
inlineprotectedvirtual |
Derived classes may implement some custom data access.
Reimplemented in VirtualRobot::Manipulability.
|
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
minNeighbors | The minimum number of neighbors that have to have an entry>0 |
|
inline |
RobotNodePtr VirtualRobot::WorkspaceRepresentation::getBaseNode | ( | ) |
The base node of this workspace data.
|
inline |
|
inline |
VirtualRobot::WorkspaceDataPtr VirtualRobot::WorkspaceRepresentation::getData | ( | ) |
Returns the raw data.
float VirtualRobot::WorkspaceRepresentation::getDiscretizeParameterRotation | ( | ) |
float VirtualRobot::WorkspaceRepresentation::getDiscretizeParameterTranslation | ( | ) |
unsigned char VirtualRobot::WorkspaceRepresentation::getEntry | ( | const Eigen::Matrix4f & | globalPose | ) | const |
Return corresponding entry of workspace data
|
virtual |
int VirtualRobot::WorkspaceRepresentation::getMaxEntry | ( | ) | const |
Returns the maximum entry of a voxel.
|
virtual |
Searches all angle entries (x3,x4,x5) for maximum entry. (x0,x1,x2) is the voxel position.
|
virtual |
Returns the maximum workspace entry that can be achieved by an arbitrary orientation at the given position.
|
virtual |
Returns the maximum that can be achieved by calling sumAngleReachabilities()
|
virtual |
RobotNodeSetPtr VirtualRobot::WorkspaceRepresentation::getNodeSet | ( | ) |
The kinematic chain that is covered by this workspace data.
|
virtual |
MathTools::OOBB VirtualRobot::WorkspaceRepresentation::getOOBB | ( | bool | achievedValues = false | ) | const |
The bounding box in global frame.
achievedValues | If not set the bounding box as defined on construction is returned. If set the min/max achieved positions are used. |
Eigen::Matrix4f VirtualRobot::WorkspaceRepresentation::getPoseFromVoxel | ( | unsigned int | v[6], |
bool | transformToGlobalPose = true |
||
) |
Computes center of corresponding voxel in global coord system.
Eigen::Matrix4f VirtualRobot::WorkspaceRepresentation::getPoseFromVoxel | ( | float | v[6], |
bool | transformToGlobalPose = true |
||
) |
bool VirtualRobot::WorkspaceRepresentation::getPoseFromVoxel | ( | unsigned int | x[], |
float | v[] | ||
) | const |
|
inline |
RobotNodePtr VirtualRobot::WorkspaceRepresentation::getTCP | ( | ) |
The corresponding TCP.
|
inline |
|
protectedvirtual |
|
protectedvirtual |
|
virtual |
get entry of given voxel.
|
virtual |
Get the corresponding voxel. If false is returned the pose is outside the covered workspace.
|
virtual |
|
virtual |
Get the corresponding voxel coordinates. If false is returned the position is outside the covered workspace.
|
virtual |
float VirtualRobot::WorkspaceRepresentation::getVoxelSize | ( | int | dim | ) | const |
returns the extends of a voxel at corresponding dimension.
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.
|
virtual |
Returns true if for the given 3d position is at least one entry >0
x | Voxel position x0 |
y | Voxel position x1 |
z | Voxel position x2 |
|
virtual |
Initialize and reset all data.
nodeSet | The robot node set that should be considered for workspace (e.g. reachability) analysis. |
discretizeStepTranslation | The extend of a voxel dimension in translational dimensions (x,y,z) [mm] |
discretizeStepRotation | The extend of a voxel dimension in rotational dimensions (roll, pitch, yaw) [rad] |
minBounds | The minimum workspace poses (x,y,z,ro,pi,ya) given in baseNode's coordinate system [mm and rad] |
maxBounds | The maximum workspace poses (x,y,z,ro,pi,ya) given in baseNode's coordinate system [mm and rad] |
staticCollisionModel | The 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 |
dynamicCollisionModel | The 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. |
baseNode | Perform 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!) |
tcpNode | If given, the pose of this node is used for workspace calculations. If not given, the TCP node of the nodeSet is used. |
adjustOnOverflow | If set, the 8bit data is divided by 2 when one voxel entry exceeds 255. Otherwise the entries remain at 255. |
void VirtualRobot::WorkspaceRepresentation::invalidateBehindRobot | ( | bool | inverted = false | ) |
bool VirtualRobot::WorkspaceRepresentation::isCovered | ( | const Eigen::Matrix4f & | globalPose | ) |
Returns true, if the corresponding voxel entry is not zero.
bool VirtualRobot::WorkspaceRepresentation::isCovered | ( | unsigned int | v[6] | ) |
Returns true, if voxel entry is not zero.
|
virtual |
Load the workspace data from a binary file. Exceptions are thrown on case errors are detected.
void VirtualRobot::WorkspaceRepresentation::matrix2Vector | ( | const Eigen::Matrix4f & | m, |
float | x[6] | ||
) | const |
Convert a 4x4 matrix to a pos + ori vector.
|
virtual |
Print status information
|
virtual |
Reset all data.
Eigen::Matrix4f VirtualRobot::WorkspaceRepresentation::sampleCoveredPose | ( | ) |
returns a random pose that is covered by the workspace data
|
virtual |
Store the workspace data to a binary file. Exceptions are thrown on case errors are detected.
|
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.
|
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.
void VirtualRobot::WorkspaceRepresentation::setEntry | ( | const Eigen::Matrix4f & | poseGlobal, |
unsigned char | e | ||
) |
void VirtualRobot::WorkspaceRepresentation::setEntryCheckNeighbors | ( | const Eigen::Matrix4f & | poseGlobal, |
unsigned char | e, | ||
unsigned int | neighborVoxels | ||
) |
void VirtualRobot::WorkspaceRepresentation::setOrientationType | ( | eOrientationType | t | ) |
Usually not needed. Don't call this method after data has been loaded or created!
|
virtual |
Generate a random configuration for the robot node set. This configuration is within the joint limits of the current robot node set.
nodeSet | The nodes. If not given, the standard nodeSet is used. |
checkForSelfCollisions | Build a collision-free configuration. If true, random configs are generated until one is collision-free. |
void VirtualRobot::WorkspaceRepresentation::setVoxelEntry | ( | unsigned int | v[6], |
unsigned char | e | ||
) |
|
virtual |
Sums all angle (x3,x4,x5) entries for the given position.
|
virtual |
void VirtualRobot::WorkspaceRepresentation::toGlobalVec | ( | Eigen::Vector3f & | positionLocal | ) | const |
|
virtual |
void VirtualRobot::WorkspaceRepresentation::toLocalVec | ( | Eigen::Vector3f & | positionGlobal | ) | const |
|
protected |
Uncompress the data.
void VirtualRobot::WorkspaceRepresentation::vector2Matrix | ( | const float | x[6], |
Eigen::Matrix4f & | m | ||
) | const |
void VirtualRobot::WorkspaceRepresentation::vector2Matrix | ( | const Eigen::Vector3f & | pos, |
const Eigen::Vector3f & | rot, | ||
Eigen::Matrix4f & | m | ||
) | const |
|
friend |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef int32_t VirtualRobot::WorkspaceRepresentation::ioIntTypeWrite |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
Specifies how the rotation part (x[3],x[4],x[5]) of an 6D voxel entry is encoded.
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |