Simox  2.3.74.0
VirtualRobot Namespace Reference

Namespaces

 FileIO
 
 MathTools
 
 Primitive
 

Data Structures

class  AdvancedIKSolver
 
class  BaseIO
 
class  BasicGraspQualityMeasure
 An interface class for grasp quality algorithms. A basic quality score, relying on the number of contacts, is served by this implementation. More...
 
class  BoundingBox
 
class  CameraSensor
 
class  CameraSensorFactory
 
class  CDManager
 
class  ChainedGrasp
 
struct  Circle
 
class  CoinVisualization
 
class  CoinVisualizationFactory
 
class  CoinVisualizationNode
 
class  CollisionChecker
 
class  CollisionCheckerDummy
 
class  CollisionCheckerImplementation
 
class  CollisionCheckerPQP
 
class  CollisionModel
 
class  CollisionModelDummy
 
class  CollisionModelImplementation
 
class  CollisionModelPQP
 
class  ColorMap
 
class  CoMIK
 
class  ConstrainedHierarchicalIK
 
class  ConstrainedIK
 
class  ConstrainedOptimizationIK
 
class  ConstrainedStackedIK
 
class  Constraint
 
class  ContactSensor
 
class  ContactSensorFactory
 
struct  DepthRenderData
 Used for a Coin3d callback to store the zBuffer. More...
 
class  DHParameter
 
class  DifferentialIK
 Encapsulates a differential inverse kinematics for the virtual robot. More...
 
class  EndEffector
 
class  EndEffectorActor
 
class  FeetPosture
 
class  ForceTorqueSensor
 
class  ForceTorqueSensorFactory
 
class  GazeIK
 
class  GenericIKSolver
 
class  Grasp
 
class  GraspableSensorizedObject
 
class  GraspSet
 
class  HierarchicalIK
 
class  IKSolver
 
class  JacobiProvider
 
class  JointLimitAvoidanceJacobi
 
class  KinematicChain
 
class  LinkedCoordinate
 This class provides intelligent coordinates for the virtual robot. More...
 
class  LocalRobot
 
class  Manipulability
 
class  ManipulationObject
 
struct  MultiCollisionResult
 
class  NaturalPosture
 
struct  NodeMappingElement
 
class  ObjectIO
 
class  Obstacle
 
class  OptimizationFunctionSetup
 
class  PoseQualityExtendedManipulability
 
class  PoseQualityManipulability
 
class  PoseQualityMeasurement
 
class  PositionSensor
 
class  PositionSensorFactory
 
class  Reachability
 
class  Robot
 
class  RobotConfig
 
class  RobotFactory
 
class  RobotIO
 
class  RobotNode
 
class  RobotNodeActuator
 
struct  robotNodeDef
 
class  RobotNodeFactory
 
class  RobotNodeFixed
 
class  RobotNodeFixedFactory
 
class  RobotNodeHemisphere
 
class  RobotNodeHemisphereFactory
 
class  RobotNodePrismatic
 
class  RobotNodePrismaticFactory
 
class  RobotNodeRevolute
 
class  RobotNodeRevoluteFactory
 
class  RobotNodeSet
 
struct  robotStructureDef
 
class  RuntimeEnvironment
 
class  Scene
 
class  SceneIO
 
class  SceneObject
 
class  SceneObjectSet
 
class  Sensor
 
class  SensorFactory
 
struct  SingleCollisionPair
 
class  SphereApproximator
 
class  StackedIK
 
class  SupportPolygon
 
class  Trajectory
 
class  TriMeshModel
 
class  TriMeshUtils
 
struct  TriTriIntersection
 
class  Units
 
class  VirtualRobotCheckException
 Exception class thrown by VR_CHECK_* macros. More...
 
class  VirtualRobotException
 
class  Visualization
 
class  VisualizationFactory
 
class  VisualizationNode
 
class  VoxelTree6D
 
class  VoxelTree6DElement
 
class  VoxelTreeND
 
class  VoxelTreeNDElement
 
class  WorkspaceData
 
class  WorkspaceDataArray
 
class  WorkspaceGrid
 
class  WorkspaceRepresentation
 

Typedefs

typedef CollisionModelPQP InternalCollisionModel
 
typedef std::shared_ptr< InternalCollisionModelInternalCollisionModelPtr
 
typedef std::shared_ptr< AdvancedIKSolverAdvancedIKSolverPtr
 
typedef std::shared_ptr< CoMIKCoMIKPtr
 
typedef std::shared_ptr< ConstrainedHierarchicalIKConstrainedHierarchicalIKPtr
 
typedef std::shared_ptr< ConstrainedIKConstrainedIKPtr
 
typedef std::shared_ptr< nlopt::opt > OptimizerPtr
 
typedef std::shared_ptr< ConstrainedOptimizationIKConstrainedOptimizationIKPtr
 
typedef std::shared_ptr< ConstrainedStackedIKConstrainedStackedIKPtr
 
typedef double(* OptimizationFunction) (std::vector< double > &gradient)
 
typedef std::shared_ptr< ConstraintConstraintPtr
 
typedef std::shared_ptr< DifferentialIKDifferentialIKPtr
 
typedef std::shared_ptr< FeetPostureFeetPosturePtr
 
typedef std::shared_ptr< GazeIKGazeIKPtr
 
typedef std::shared_ptr< GenericIKSolverGenericIKSolverPtr
 
typedef std::shared_ptr< HierarchicalIKHierarchicalIKPtr
 
typedef std::shared_ptr< IKSolverIKSolverPtr
 
typedef std::shared_ptr< JacobiProviderJacobiProviderPtr
 
typedef std::shared_ptr< JointLimitAvoidanceJacobiJointLimitAvoidanceJacobiPtr
 
typedef std::shared_ptr< PoseQualityExtendedManipulabilityPoseQualityExtendedManipulabilityPtr
 
typedef std::shared_ptr< RobotPoseDifferentialIK > RobotPoseDifferentialIKPtr
 
typedef std::shared_ptr< StackedIKStackedIKPtr
 
typedef std::shared_ptr< SupportPolygonSupportPolygonPtr
 
typedef std::shared_ptr< CameraSensorCameraSensorPtr
 
typedef std::shared_ptr< ContactSensorContactSensorPtr
 
typedef std::shared_ptr< ForceTorqueSensorForceTorqueSensorPtr
 
typedef std::shared_ptr< PositionSensorPositionSensorPtr
 
typedef std::shared_ptr< RobotNodeActuatorRobotNodeActuatorPtr
 
using RobotNodeHemispherePtr = std::shared_ptr< class RobotNodeHemisphere >
 
typedef std::shared_ptr< RobotNodePrismaticRobotNodePrismaticPtr
 
typedef std::shared_ptr< RobotNodeRevoluteRobotNodeRevolutePtr
 
typedef std::shared_ptr< SensorSensorPtr
 
typedef std::shared_ptr< SensorFactorySensorFactoryPtr
 
typedef std::shared_ptr< VisualizationFactory::ColorColorPtr
 
typedef std::shared_ptr< ManipulabilityManipulabilityPtr
 
typedef std::shared_ptr< GraspableSensorizedObjectGraspableSensorizedObjectPtr
 
using NodeMapping = std::unordered_map< std::string, NodeMappingElement >
 
typedef std::shared_ptr< TSRConstraint > TSRConstraintPtr
 
typedef std::shared_ptr< BalanceConstraint > BalanceConstraintPtr
 
typedef std::shared_ptr< PoseConstraint > PoseConstraintPtr
 
typedef std::shared_ptr< PositionConstraint > PositionConstraintPtr
 
typedef std::shared_ptr< OrientationConstraint > OrientationConstraintPtr
 
typedef std::shared_ptr< RobotNodeRobotNodePtr
 
typedef std::shared_ptr< RobotNodeSetRobotNodeSetPtr
 
typedef std::shared_ptr< KinematicChainKinematicChainPtr
 
typedef std::weak_ptr< RobotNodeRobotNodeWeakPtr
 
typedef std::shared_ptr< RobotNodeFactoryRobotNodeFactoryPtr
 
typedef std::shared_ptr< RobotRobotPtr
 
typedef std::weak_ptr< RobotRobotWeakPtr
 
typedef std::shared_ptr< EndEffectorEndEffectorPtr
 
typedef std::shared_ptr< EndEffectorActorEndEffectorActorPtr
 
typedef std::shared_ptr< CollisionModelCollisionModelPtr
 
typedef std::shared_ptr< CollisionCheckerCollisionCheckerPtr
 
typedef std::shared_ptr< SceneObjectSetSceneObjectSetPtr
 
typedef std::shared_ptr< TriMeshModelTriMeshModelPtr
 
typedef std::shared_ptr< SceneObjectSceneObjectPtr
 
typedef std::weak_ptr< SceneObjectSceneObjectWeakPtr
 
typedef std::shared_ptr< ObstacleObstaclePtr
 
typedef std::shared_ptr< VisualizationVisualizationPtr
 
typedef std::shared_ptr< VisualizationNodeVisualizationNodePtr
 
typedef std::shared_ptr< VisualizationFactoryVisualizationFactoryPtr
 
typedef std::shared_ptr< WorkspaceDataWorkspaceDataPtr
 
typedef std::shared_ptr< WorkspaceDataArrayWorkspaceDataArrayPtr
 
typedef std::shared_ptr< WorkspaceRepresentationWorkspaceRepresentationPtr
 
typedef std::shared_ptr< ReachabilityReachabilityPtr
 
typedef std::shared_ptr< SceneScenePtr
 
typedef std::shared_ptr< RobotConfigRobotConfigPtr
 
typedef std::shared_ptr< GraspGraspPtr
 
typedef std::shared_ptr< ChainedGraspChainedGraspPtr
 
typedef std::shared_ptr< GraspSetGraspSetPtr
 
typedef std::weak_ptr< GraspableSensorizedObjectGraspableSensorizedObjectWeakPtr
 
typedef std::shared_ptr< ManipulationObjectManipulationObjectPtr
 
typedef std::shared_ptr< CDManagerCDManagerPtr
 
typedef std::shared_ptr< PoseQualityMeasurementPoseQualityMeasurementPtr
 
typedef std::shared_ptr< PoseQualityManipulabilityPoseQualityManipulabilityPtr
 
typedef std::shared_ptr< TrajectoryTrajectoryPtr
 
typedef std::shared_ptr< SphereApproximatorSphereApproximatorPtr
 
typedef std::shared_ptr< BasicGraspQualityMeasureBasicGraspQualityMeasurePtr
 
typedef std::shared_ptr< WorkspaceGridWorkspaceGridPtr
 
typedef std::shared_ptr< LocalRobotLocalRobotPtr
 
typedef std::shared_ptr< CoinVisualizationCoinVisualizationPtr
 
typedef std::shared_ptr< CoinVisualizationFactoryCoinVisualizationFactoryPtr
 
typedef std::map< const SoPrimitiveVertex *, int > CoinVertexIndexMap
 
typedef std::shared_ptr< CoinVisualizationNodeCoinVisualizationNodePtr
 

Functions

static TriTriIntersection intersectTriangles (Eigen::Vector3f const &U0, Eigen::Vector3f const &U1, Eigen::Vector3f const &U2, Eigen::Vector3f const &V0, Eigen::Vector3f const &V1, Eigen::Vector3f const &V2)
 
class deprecated ("MMMTools_LegacyConverter")]] VIRTUAL_ROBOT_IMPORT_EXPORT RobotPoseDifferentialIK
 
double uniformDeviate (int seed)
 
bool toBool (const std::string &strRepr) noexcept
 
Eigen::Matrix3f VIRTUAL_ROBOT_IMPORT_EXPORT quat2eigen3f (float qx, float qy, float qz, float qw)
 
std::mt19937_64 & PRNG64Bit ()
 
std::mt19937_64::result_type RandomNumber ()
 
float RandomFloat ()
 
float RandomFloat (float min, float max)
 
static boost::program_options::options_description RuntimeEnvironment_makeOptionsDescription ()
 Make the options description based on the added keys and flags. More...
 
static void RuntimeEnvironment_processParsedOptions (const boost::program_options::parsed_options &parsed)
 
static std::size_t getMaxLength (const std::vector< std::pair< std::string, std::string >> &items)
 
static std::string padding (std::size_t current, std::size_t target, char c=' ')
 
Circle projectedBoundingCircle (const Robot &robot)
 
void init (const std::string &appName)
 
void init (int &argc, char *argv[], const std::string &appName)
 
std::ifstream::pos_type getFilesize (const char *filename)
 
void getZBuffer (void *userdata)
 Used for a Coin3d callback to store the zBuffer. More...
 

Variables

static const float limit = 1.0
 
const simox::meta::EnumNames< RobotNodeHemisphere::RoleRoleNames
 
constexpr int INVALID_VALUE = -1
 
static bool RuntimeEnvironment_pathInitialized = false
 
static std::string RuntimeEnvironment_caption = "Simox runtime options"
 
static std::vector< std::pair< std::string, std::string > > RuntimeEnvironment_processKeys
 Pairs of (key, description). If not given, description is empty. More...
 
static std::vector< std::pair< std::string, std::string > > RuntimeEnvironment_processFlags
 Pairs of (flag, description). If not given, description is empty. More...
 
static std::vector< std::string > RuntimeEnvironment_dataPaths
 
static std::vector< std::string > RuntimeEnvironment_unrecognizedOptions
 
static std::map< std::string, std::string > RuntimeEnvironment_keyValues
 
static std::set< std::string > RuntimeEnvironment_flags
 
static bool RuntimeEnvironment_helpFlag = false
 
std::string globalAppName
 

Detailed Description

This file is part of Simox.

Simox is free software; you can redistribute it and/or modify it under the terms of the GNU Lesser General Public License as published by the Free Software Foundation; either version 2 of the License, or (at your option) any later version.

Simox is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License for more details.

You should have received a copy of the GNU Lesser General Public License along with this program. If not, see http://www.gnu.org/licenses/.

Date
2011-02-24
Author
Nikolaus Vahrenkamp

This file is part of Simox.

Simox is free software; you can redistribute it and/or modify it under the terms of the GNU Lesser General Public License as published by the Free Software Foundation; either version 2 of the License, or (at your option) any later version.

Simox is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License for more details.

You should have received a copy of the GNU Lesser General Public License along with this program. If not, see http://www.gnu.org/licenses/.

Author
Nikolaus Vahrenkamp
Author
Manfred Kroehnert , Nikolaus Vahrenkamp

This file is part of Simox.

Simox is free software; you can redistribute it and/or modify it under the terms of the GNU Lesser General Public License as published by the Free Software Foundation; either version 2 of the License, or (at your option) any later version.

Simox is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License for more details.

You should have received a copy of the GNU Lesser General Public License along with this program. If not, see http://www.gnu.org/licenses/.

Author
Manfred Kroehnert, Nikolaus Vahrenkamp
Author
Nikolaus Vahrenkamp
Manfred Kroehnert

This file is part of Simox.

Simox is free software; you can redistribute it and/or modify it under the terms of the GNU Lesser General Public License as published by the Free Software Foundation; either version 2 of the License, or (at your option) any later version.

Simox is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License for more details.

You should have received a copy of the GNU Lesser General Public License along with this program. If not, see http://www.gnu.org/licenses/.

Author
Manfred Kroehnert, Nikolaus Vahrenkamp
Author
Nikolaus Vahrenkamp

This file is part of Simox.

Simox is free software; you can redistribute it and/or modify it under the terms of the GNU Lesser General Public License as published by the Free Software Foundation; either version 2 of the License, or (at your option) any later version.

Simox is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License for more details.

You should have received a copy of the GNU Lesser General Public License along with this program. If not, see http://www.gnu.org/licenses/.

Author
Nikolaus Vahrenkamp

This file is part of Simox.

Simox is free software; you can redistribute it and/or modify it under the terms of the GNU Lesser General Public License as published by the Free Software Foundation; either version 2 of the License, or (at your option) any later version.

Simox is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License for more details.

You should have received a copy of the GNU Lesser General Public License along with this program. If not, see http://www.gnu.org/licenses/.

Author
Andre Meixner

This file is part of Simox.

Simox is free software; you can redistribute it and/or modify it under the terms of the GNU Lesser General Public License as published by the Free Software Foundation; either version 2 of the License, or (at your option) any later version.

Simox is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License for more details.

You should have received a copy of the GNU Lesser General Public License along with this program. If not, see http://www.gnu.org/licenses/.

Author
Peter Kaiser, Nikolaus Vahrenkamp

This file is part of Simox.

Simox is free software; you can redistribute it and/or modify it under the terms of the GNU Lesser General Public License as published by the Free Software Foundation; either version 2 of the License, or (at your option) any later version.

Simox is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License for more details.

You should have received a copy of the GNU Lesser General Public License along with this program. If not, see http://www.gnu.org/licenses/.

Author
Peter Kaiser

This file is part of Simox.

Simox is free software; you can redistribute it and/or modify it under the terms of the GNU Lesser General Public License as published by the Free Software Foundation; either version 2 of the License, or (at your option) any later version.

Simox is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License for more details.

You should have received a copy of the GNU Lesser General Public License along with this program. If not, see http://www.gnu.org/licenses/.

Author
Peter Kaiser
Matthias Hadlich

This file is part of Simox.

Simox is free software; you can redistribute it and/or modify it under the terms of the GNU Lesser General Public License as published by the Free Software Foundation; either version 2 of the License, or (at your option) any later version.

Simox is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License for more details.

You should have received a copy of the GNU Lesser General Public License along with this program. If not, see http://www.gnu.org/licenses/.

Author
Stefan Ulbrich, Nikolaus Vahrenkamp

This file is part of Simox.

Simox is free software; you can redistribute it and/or modify it under the terms of the GNU Lesser General Public License as published by the Free Software Foundation; either version 2 of the License, or (at your option) any later version.

Simox is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License for more details.

You should have received a copy of the GNU Lesser General Public License along with this program. If not, see http://www.gnu.org/licenses/.

Author
Nikolaus Vahrenkamp

This file is part of Simox.

Simox is free software; you can redistribute it and/or modify it under the terms of the GNU Lesser General Public License as published by the Free Software Foundation; either version 2 of the License, or (at your option) any later version.

Simox is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License for more details.

You should have received a copy of the GNU Lesser General Public License along with this program. If not, see http://www.gnu.org/licenses/.

Author
Nikolaus Vahrenkamp

This file is part of Simox.

Simox is free software; you can redistribute it and/or modify it under the terms of the GNU Lesser General Public License as published by the Free Software Foundation; either version 2 of the License, or (at your option) any later version.

Simox is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License for more details.

You should have received a copy of the GNU General Public License along with this program. If not, see http://www.gnu.org/licenses/.

Author
Nikolaus Vahrenkamp <vahrenkamp at="" users="" dot="" sf="" dot="" net>="">

This file is part of Simox.

Simox is free software; you can redistribute it and/or modify it under the terms of the GNU Lesser General Public License as published by the Free Software Foundation; either version 2 of the License, or (at your option) any later version.

Simox is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License for more details.

You should have received a copy of the GNU Lesser General Public License along with this program. If not, see http://www.gnu.org/licenses/.

Author
Patrick Niklaus

This file is part of Simox.

Simox is free software; you can redistribute it and/or modify it under the terms of the GNU Lesser General Public License as published by the Free Software Foundation; either version 2 of the License, or (at your option) any later version.

Simox is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License for more details.

You should have received a copy of the GNU Lesser General Public License along with this program. If not, see http://www.gnu.org/licenses/.

Author
Manfred Kroehnert, Nikolaus Vahrenkamp
Author
Manfred Kroehnert

This file is part of Simox.

Simox is free software; you can redistribute it and/or modify it under the terms of the GNU Lesser General Public License as published by the Free Software Foundation; either version 2 of the License, or (at your option) any later version.

Simox is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License for more details.

You should have received a copy of the GNU Lesser General Public License along with this program. If not, see http://www.gnu.org/licenses/.

Author
Rainer Kartmann
Author
Rainer Kartmann
Author
David Gonzales, Nikolaus Vahrenkamp

This file is part of Simox.

Simox is free software; you can redistribute it and/or modify it under the terms of the GNU Lesser General Public License as published by the Free Software Foundation; either version 2 of the License, or (at your option) any later version.

Simox is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License for more details.

You should have received a copy of the GNU Lesser General Public License along with this program. If not, see http://www.gnu.org/licenses/.

Author
David Gonzales, Nikolaus Vahrenkamp
Author
Manfred Kroehnert
Nikolaus Vahrenkamp

This file is part of Simox.

Simox is free software = 0; you can redistribute it and/or modify it under the terms of the GNU Lesser General Public License as published by the Free Software Foundation = 0; either version 2 of the License, or (at your option) any later version.

Simox is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY = 0; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License for more details.

You should have received a copy of the GNU Lesser General Public License along with this program. If not, see http://www.gnu.org/licenses/.

Author
Peter Kaiser, Nikolaus Vahrenkamp

This file is part of Simox.

Simox is free software; you can redistribute it and/or modify it under the terms of the GNU Lesser General Public License as published by the Free Software Foundation; either version 2 of the License, or (at your option) any later version.

Simox is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License for more details.

You should have received a copy of the GNU General Public License along with this program. If not, see http://www.gnu.org/licenses/.

Author
Stefan Ulbrich

This file is part of Simox.

Simox is free software; you can redistribute it and/or modify it under the terms of the GNU Lesser General Public License as published by the Free Software Foundation; either version 2 of the License, or (at your option) any later version.

Simox is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License for more details.

You should have received a copy of the GNU Lesser General Public License along with this program. If not, see http://www.gnu.org/licenses/.

Author
Raphael Grimm

This file is part of Simox.

Simox is free software; you can redistribute it and/or modify it under the terms of the GNU Lesser General Public License as published by the Free Software Foundation; either version 2 of the License, or (at your option) any later version.

Simox is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License for more details.

You should have received a copy of the GNU Lesser General Public License along with this program. If not, see http://www.gnu.org/licenses/.

Author
Kai Welke, Nikolaus Vahrenkamp
Author
Manfred Kroehnert <mkroehnert _at_="" users="" dot="" sourceforge="" dot="" net>="">

The macros VR_CHECK_*() defined in this file can be used as "soft" assertions. That is, they can be used to check some condition and, if this condition fails, throw an exception (of type VirtualRobotCheckException). Thrown exceptions give information about where they were thrown and what condition failed.

All macros are defined in two versions, one taking a "hint", explaining what is checked, and one taking no hint.

Hints hould be formulated "positively", i.e. what condition is tested and what must be true, not what went wrong otherwise. For example:

VR_CHECK_EQUAL_HINT(vector.size(), 3, "Vector must have exactly 3 elements.");
VR_CHECK_HINT(pointer, "Pointer must not be null.");
*not:* VR_CHECK_HINT(pointer, "Pointer is null.");
Author
Nikolaus Vahrenkamp
Manfred Kroehnert
Author
Manfred Kroehnert, Nikolaus Vahrenkamp

Typedef Documentation

◆ AdvancedIKSolverPtr

◆ BalanceConstraintPtr

typedef std::shared_ptr<BalanceConstraint> VirtualRobot::BalanceConstraintPtr

◆ BasicGraspQualityMeasurePtr

◆ CameraSensorPtr

typedef std::shared_ptr<CameraSensor> VirtualRobot::CameraSensorPtr

◆ CDManagerPtr

typedef std::shared_ptr<CDManager> VirtualRobot::CDManagerPtr

◆ ChainedGraspPtr

typedef std::shared_ptr<ChainedGrasp> VirtualRobot::ChainedGraspPtr

◆ CoinVertexIndexMap

typedef std::map<const SoPrimitiveVertex*, int> VirtualRobot::CoinVertexIndexMap

◆ CoinVisualizationFactoryPtr

◆ CoinVisualizationNodePtr

◆ CoinVisualizationPtr

◆ CollisionCheckerPtr

◆ CollisionModelPtr

◆ ColorPtr

◆ CoMIKPtr

typedef std::shared_ptr< CoMIK > VirtualRobot::CoMIKPtr

◆ ConstrainedHierarchicalIKPtr

◆ ConstrainedIKPtr

◆ ConstrainedOptimizationIKPtr

◆ ConstrainedStackedIKPtr

◆ ConstraintPtr

typedef std::shared_ptr< Constraint > VirtualRobot::ConstraintPtr

◆ ContactSensorPtr

typedef std::shared_ptr< ContactSensor > VirtualRobot::ContactSensorPtr

◆ DifferentialIKPtr

typedef std::shared_ptr< DifferentialIK > VirtualRobot::DifferentialIKPtr

◆ EndEffectorActorPtr

◆ EndEffectorPtr

typedef std::shared_ptr<EndEffector> VirtualRobot::EndEffectorPtr

◆ FeetPosturePtr

typedef std::shared_ptr<FeetPosture> VirtualRobot::FeetPosturePtr

◆ ForceTorqueSensorPtr

◆ GazeIKPtr

typedef std::shared_ptr<GazeIK> VirtualRobot::GazeIKPtr

◆ GenericIKSolverPtr

◆ GraspableSensorizedObjectPtr

◆ GraspableSensorizedObjectWeakPtr

◆ GraspPtr

typedef std::shared_ptr<Grasp> VirtualRobot::GraspPtr

◆ GraspSetPtr

typedef std::shared_ptr<GraspSet> VirtualRobot::GraspSetPtr

◆ HierarchicalIKPtr

typedef std::shared_ptr< HierarchicalIK > VirtualRobot::HierarchicalIKPtr

◆ IKSolverPtr

typedef std::shared_ptr<IKSolver> VirtualRobot::IKSolverPtr

◆ InternalCollisionModel

◆ InternalCollisionModelPtr

◆ JacobiProviderPtr

◆ JointLimitAvoidanceJacobiPtr

◆ KinematicChainPtr

◆ LocalRobotPtr

typedef std::shared_ptr<LocalRobot> VirtualRobot::LocalRobotPtr

◆ ManipulabilityPtr

◆ ManipulationObjectPtr

◆ NodeMapping

using VirtualRobot::NodeMapping = typedef std::unordered_map<std::string, NodeMappingElement>

◆ ObstaclePtr

typedef std::shared_ptr<Obstacle> VirtualRobot::ObstaclePtr

◆ OptimizationFunction

typedef double(* VirtualRobot::OptimizationFunction) (std::vector< double > &gradient)

◆ OptimizerPtr

typedef std::shared_ptr<nlopt::opt> VirtualRobot::OptimizerPtr

◆ OrientationConstraintPtr

typedef std::shared_ptr<OrientationConstraint> VirtualRobot::OrientationConstraintPtr

◆ PoseConstraintPtr

typedef std::shared_ptr<PoseConstraint> VirtualRobot::PoseConstraintPtr

◆ PoseQualityExtendedManipulabilityPtr

◆ PoseQualityManipulabilityPtr

◆ PoseQualityMeasurementPtr

◆ PositionConstraintPtr

typedef std::shared_ptr<PositionConstraint> VirtualRobot::PositionConstraintPtr

◆ PositionSensorPtr

typedef std::shared_ptr< PositionSensor > VirtualRobot::PositionSensorPtr

◆ ReachabilityPtr

typedef std::shared_ptr<Reachability> VirtualRobot::ReachabilityPtr

◆ RobotConfigPtr

typedef std::shared_ptr<RobotConfig> VirtualRobot::RobotConfigPtr

◆ RobotNodeActuatorPtr

◆ RobotNodeFactoryPtr

◆ RobotNodeHemispherePtr

using VirtualRobot::RobotNodeHemispherePtr = typedef std::shared_ptr<class RobotNodeHemisphere>

◆ RobotNodePrismaticPtr

◆ RobotNodePtr

typedef std::shared_ptr<RobotNode> VirtualRobot::RobotNodePtr

◆ RobotNodeRevolutePtr

◆ RobotNodeSetPtr

typedef std::shared_ptr<RobotNodeSet> VirtualRobot::RobotNodeSetPtr

◆ RobotNodeWeakPtr

typedef std::weak_ptr<RobotNode> VirtualRobot::RobotNodeWeakPtr

◆ RobotPoseDifferentialIKPtr

typedef std::shared_ptr<RobotPoseDifferentialIK> VirtualRobot::RobotPoseDifferentialIKPtr

◆ RobotPtr

typedef std::shared_ptr<Robot> VirtualRobot::RobotPtr

◆ RobotWeakPtr

typedef std::weak_ptr<Robot> VirtualRobot::RobotWeakPtr

◆ SceneObjectPtr

typedef std::shared_ptr<SceneObject> VirtualRobot::SceneObjectPtr

◆ SceneObjectSetPtr

◆ SceneObjectWeakPtr

◆ ScenePtr

typedef std::shared_ptr<Scene> VirtualRobot::ScenePtr

◆ SensorFactoryPtr

◆ SensorPtr

typedef std::shared_ptr< Sensor > VirtualRobot::SensorPtr

◆ SphereApproximatorPtr

◆ StackedIKPtr

typedef std::shared_ptr<StackedIK> VirtualRobot::StackedIKPtr

◆ SupportPolygonPtr

typedef std::shared_ptr< SupportPolygon > VirtualRobot::SupportPolygonPtr

◆ TrajectoryPtr

typedef std::shared_ptr<Trajectory> VirtualRobot::TrajectoryPtr

◆ TriMeshModelPtr

typedef std::shared_ptr<TriMeshModel> VirtualRobot::TriMeshModelPtr

◆ TSRConstraintPtr

typedef std::shared_ptr<TSRConstraint> VirtualRobot::TSRConstraintPtr

◆ VisualizationFactoryPtr

◆ VisualizationNodePtr

◆ VisualizationPtr

◆ WorkspaceDataArrayPtr

◆ WorkspaceDataPtr

◆ WorkspaceGridPtr

◆ WorkspaceRepresentationPtr

Function Documentation

◆ deprecated()

class VirtualRobot::deprecated ( "MMMTools_LegacyConverter"  )

Initialize a Jacobian object.

Parameters
rnsThe robotNodes (i.e., joints) for which the Jacobians should be calculated.
coordSystemThe coordinate system in which the Jacobians are defined. By default the global coordinate system is used.

Compute a single IK step.

Parameters
stepSizeControls the amount of error to be reduced in each step: $ 0 < \beta \leq 1 $
Returns
The changes $\Delta \theta$ in the joint angles.
Note
{Note} This does not affect the joints values of the robot.

Computes the complete inverse kinematics.

Parameters
stepSizeControls the amount of error to be reduced in each step: $ 0 < \beta \leq 1 $
maxStepsMaximal numbers of steps.
minChangeThe minimal change in joint angles (euclidean distance in radians)
performMinOneStepIf set, at least one step is performed (helps escaping local minima, but may also cause pose jittering)
Note
{Note} Sets the node's joint angles automatically.

If enabled (standard), joint limits are considered via box constraints.

◆ getFilesize()

std::ifstream::pos_type VirtualRobot::getFilesize ( const char *  filename)

◆ getMaxLength()

static std::size_t VirtualRobot::getMaxLength ( const std::vector< std::pair< std::string, std::string >> &  items)
static

◆ getZBuffer()

void VirtualRobot::getZBuffer ( void *  userdata)

Used for a Coin3d callback to store the zBuffer.

Parameters
userdataThe datastructure to store the data to.
See also
renderOffscreenRgbDepthPointcloud

◆ init() [1/2]

void VIRTUAL_ROBOT_IMPORT_EXPORT VirtualRobot::init ( const std::string &  appName)

◆ init() [2/2]

void VIRTUAL_ROBOT_IMPORT_EXPORT VirtualRobot::init ( int &  argc,
char *  argv[],
const std::string &  appName 
)

Initialize the runtime envionment. This method calls VisualizationFactory::init().

◆ intersectTriangles()

static TriTriIntersection VirtualRobot::intersectTriangles ( Eigen::Vector3f const &  U0,
Eigen::Vector3f const &  U1,
Eigen::Vector3f const &  U2,
Eigen::Vector3f const &  V0,
Eigen::Vector3f const &  V1,
Eigen::Vector3f const &  V2 
)
static

◆ padding()

static std::string VirtualRobot::padding ( std::size_t  current,
std::size_t  target,
char  c = ' ' 
)
static

◆ PRNG64Bit()

std::mt19937_64 VIRTUAL_ROBOT_IMPORT_EXPORT & VirtualRobot::PRNG64Bit ( )

◆ projectedBoundingCircle()

Circle VirtualRobot::projectedBoundingCircle ( const Robot robot)
inline

◆ quat2eigen3f()

Eigen::Matrix3f VIRTUAL_ROBOT_IMPORT_EXPORT VirtualRobot::quat2eigen3f ( float  qx,
float  qy,
float  qz,
float  qw 
)

◆ RandomFloat() [1/2]

float VirtualRobot::RandomFloat ( )
inline

◆ RandomFloat() [2/2]

float VirtualRobot::RandomFloat ( float  min,
float  max 
)
inline

◆ RandomNumber()

std::mt19937_64::result_type VirtualRobot::RandomNumber ( )
inline

◆ RuntimeEnvironment_makeOptionsDescription()

static boost::program_options::options_description VirtualRobot::RuntimeEnvironment_makeOptionsDescription ( )
static

Make the options description based on the added keys and flags.

◆ RuntimeEnvironment_processParsedOptions()

static void VirtualRobot::RuntimeEnvironment_processParsedOptions ( const boost::program_options::parsed_options &  parsed)
static

◆ toBool()

bool VirtualRobot::toBool ( const std::string &  strRepr)
inlinenoexcept

◆ uniformDeviate()

double VirtualRobot::uniformDeviate ( int  seed)
inline

Variable Documentation

◆ globalAppName

VIRTUAL_ROBOT_IMPORT_EXPORT std::string VirtualRobot::globalAppName

◆ INVALID_VALUE

constexpr int VirtualRobot::INVALID_VALUE = -1

◆ limit

const float VirtualRobot::limit = 1.0
static

◆ RoleNames

const simox::meta::EnumNames<RobotNodeHemisphere::Role> VirtualRobot::RoleNames
Initial value:
=
{
{ RobotNodeHemisphere::Role::FIRST, "first" },
{ RobotNodeHemisphere::Role::SECOND, "second" },
}

◆ RuntimeEnvironment_caption

std::string VirtualRobot::RuntimeEnvironment_caption = "Simox runtime options"
static

◆ RuntimeEnvironment_dataPaths

std::vector< std::string > VirtualRobot::RuntimeEnvironment_dataPaths
static

◆ RuntimeEnvironment_flags

std::set< std::string > VirtualRobot::RuntimeEnvironment_flags
static

◆ RuntimeEnvironment_helpFlag

bool VirtualRobot::RuntimeEnvironment_helpFlag = false
static

◆ RuntimeEnvironment_keyValues

std::map< std::string, std::string > VirtualRobot::RuntimeEnvironment_keyValues
static

◆ RuntimeEnvironment_pathInitialized

bool VirtualRobot::RuntimeEnvironment_pathInitialized = false
static

◆ RuntimeEnvironment_processFlags

std::vector< std::pair<std::string, std::string> > VirtualRobot::RuntimeEnvironment_processFlags
static

Pairs of (flag, description). If not given, description is empty.

◆ RuntimeEnvironment_processKeys

std::vector< std::pair<std::string, std::string> > VirtualRobot::RuntimeEnvironment_processKeys
static

Pairs of (key, description). If not given, description is empty.

◆ RuntimeEnvironment_unrecognizedOptions

std::vector< std::string > VirtualRobot::RuntimeEnvironment_unrecognizedOptions
static