Simox
2.3.74.0
|
Public Types | |
typedef std::map< std::pair< size_t, std::string >, void * > | TextureCacheMap |
![]() | |
typedef std::shared_ptr< VisualizationFactory >(* | initialisationFunction) (void *) |
Public Member Functions | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | CoinVisualizationFactory () |
~CoinVisualizationFactory () override | |
void | init (int &argc, char *argv[], const std::string &appName) override |
VisualizationNodePtr | getVisualizationFromPrimitives (const std::vector< Primitive::PrimitivePtr > &primitives, bool boundingBox=false, Color color=Color::Gray()) override |
VisualizationNodePtr | getVisualizationFromFile (const std::string &filename, bool boundingBox=false, float scaleX=1.0f, float scaleY=1.0f, float scaleZ=1.0f) override |
virtual VisualizationNodePtr | getVisualizationFromFileWithAssimp (const std::string &filename, bool boundingBox=false, float scaleX=1.0f, float scaleY=1.0f, float scaleZ=1.0f) |
virtual VisualizationNodePtr | getVisualizationFromCoin3DFile (const std::string &filename, bool boundingBox=false) |
VisualizationNodePtr | getVisualizationFromFile (const std::ifstream &ifs, bool boundingBox=false, float scaleX=1.0f, float scaleY=1.0f, float scaleZ=1.0f) override |
virtual VisualizationNodePtr | getVisualizationFromString (const std::string &modelString, bool boundingBox=false) |
virtual VisualizationPtr | getVisualization (const std::vector< VisualizationNodePtr > &visus) |
virtual VisualizationPtr | getVisualization (VisualizationNodePtr visu) |
VisualizationNodePtr | createBox (float width, float height, float depth, float colorR=0.5f, float colorG=0.5f, float colorB=0.5f) override |
VisualizationNodePtr | createLine (const Eigen::Vector3f &from, const Eigen::Vector3f &to, float width=1.0f, float colorR=0.5f, float colorG=0.5f, float colorB=0.5f) override |
VisualizationNodePtr | createLine (const Eigen::Matrix4f &from, const Eigen::Matrix4f &to, float width=1.0f, float colorR=0.5f, float colorG=0.5f, float colorB=0.5f) override |
VisualizationNodePtr | createSphere (float radius, float colorR=0.5f, float colorG=0.5f, float colorB=0.5f) override |
VisualizationNodePtr | createCylinder (float radius, float height, float colorR=0.5f, float colorG=0.5f, float colorB=0.5f) override |
VisualizationNodePtr | createCircle (float radius, float circleCompletion, float width, float colorR=1.0f, float colorG=0.5f, float colorB=0.5f, size_t numberOfCircleParts=30) override |
VisualizationNodePtr | createCoordSystem (float scaling=1.0f, std::string *text=NULL, float axisLength=100.0f, float axisSize=3.0f, int nrOfBlocks=10) override |
VisualizationNodePtr | createBoundingBox (const BoundingBox &bbox, bool wireFrame=false) override |
VisualizationNodePtr | createVertexVisualization (const Eigen::Vector3f &position, float radius, float transparency, float colorR=0.5f, float colorG=0.5f, float colorB=0.5f) override |
VisualizationNodePtr | createTriMeshModelVisualization (const TriMeshModelPtr &model, const Eigen::Matrix4f &pose=Eigen::Matrix4f::Identity(), float scaleX=1.0f, float scaleY=1.0f, float scaleZ=1.0f) override |
VisualizationNodePtr | createTriMeshModelVisualization (const TriMeshModelPtr &model, bool showNormals, const Eigen::Matrix4f &pose, bool showLines=true) override |
VisualizationNodePtr | createPlane (const Eigen::Vector3f &position, const Eigen::Vector3f &normal, float extend, float transparency, float colorR=0.5f, float colorG=0.5f, float colorB=0.5f) override |
VisualizationNodePtr | createArrow (const Eigen::Vector3f &n, float length=50.0f, float width=2.0f, const Color &color=Color::Gray()) override |
VisualizationNodePtr | createCircleArrow (float radius, float tubeRadius, float completion=1, float colorR=0.5f, float colorG=0.5f, float colorB=0.5f, float transparency=0.0f, int sides=8, int rings=30) override |
VisualizationNodePtr | createTrajectory (TrajectoryPtr t, Color colorNode=Color::Blue(), Color colorLine=Color::Gray(), float nodeSize=15.0f, float lineSize=4.0f) override |
VisualizationNodePtr | createText (const std::string &text, bool billboard=false, float scaling=1.0f, Color c=Color::Black(), float offsetX=20.0f, float offsetY=20.0f, float offsetZ=0.0f) override |
VisualizationNodePtr | createTorus (float radius, float tubeRadius, float completion=1, float colorR=0.5f, float colorG=0.5f, float colorB=0.5f, float transparency=0.0f, int sides=8, int rings=30) override |
VisualizationNodePtr | createEllipse (float x, float y, float z, bool showAxes=true, float axesHeight=4.0f, float axesWidth=8.0f) override |
void | applyDisplacement (VisualizationNodePtr o, Eigen::Matrix4f &m) override |
VisualizationNodePtr | createVisualization () override |
VisualizationNodePtr | createUnitedVisualization (const std::vector< VisualizationNodePtr > &visualizations) const override |
void | cleanup () override |
![]() | |
VisualizationFactory ()=default | |
virtual | ~VisualizationFactory ()=default |
virtual VisualizationNodePtr | createPlane (const MathTools::Plane &plane, float extend, float transparency, float colorR=0.5f, float colorG=0.5f, float colorB=0.5f) |
![]() | |
void | setDescription (const std::string &newDescription) |
std::string | getDescription () const |
Static Public Member Functions | |
static SoSeparator * | CreateConvexHull2DVisualization (const MathTools::ConvexHull2DPtr ch, MathTools::Plane &p, VisualizationFactory::Color colorInner=VisualizationFactory::Color::Blue(), VisualizationFactory::Color colorLine=VisualizationFactory::Color::Black(), float lineSize=5.0f, const Eigen::Vector3f &offset=Eigen::Vector3f::Zero()) |
static SoSeparator * | CreatePolygonVisualization (const std::vector< Eigen::Vector3f > &points, VisualizationFactory::Color colorInner=VisualizationFactory::Color::Blue(), VisualizationFactory::Color colorLine=VisualizationFactory::Color::Black(), float lineSize=4.0f) |
static SoSeparator * | CreatePolygonVisualization (const std::vector< Eigen::Vector3f > &points, VisualizationFactory::PhongMaterial mat, VisualizationFactory::Color colorLine=VisualizationFactory::Color::Black(), float lineSize=4.0f) |
static SoSeparator * | CreatePlaneVisualization (const Eigen::Vector3f &position, const Eigen::Vector3f &normal, float extend, float transparency, bool grid=true, float colorR=0.5f, float colorG=0.5f, float colorB=0.5f, std::string textureFile=std::string()) |
static SoSeparator * | CreateCoordSystemVisualization (float scaling=1.0f, std::string *text=NULL, float axisLength=100.0f, float axisSize=3.0f, int nrOfBlocks=10) |
static SoSeparator * | CreateBoundingBox (SoNode *ivModel, bool wireFrame=false) |
static SoSeparator * | CreateGrid (float width, float depth, float widthMosaic, float depthMosaic, bool InvertNormal, const char *pFileName, float Transparency) |
static SoSeparator * | CreateBBoxVisualization (const BoundingBox &bbox, bool wireFrame=false) |
static SoSeparator * | CreatePointVisualization (const MathTools::ContactPoint &point, bool showNormals=false) |
static SoSeparator * | CreatePointsVisualization (const std::vector< MathTools::ContactPoint > &points, bool showNormals=false) |
static SoSeparator * | CreateArrow (const Eigen::Vector3f &pt, const Eigen::Vector3f &n, float length=50.0f, float width=2.0f, const Color &color=Color::Gray()) |
static SoSeparator * | CreateArrow (const Eigen::Vector3f &n, float length=50.0f, float width=2.0f, const Color &color=Color::Gray()) |
static SoSeparator * | CreateVertexVisualization (const Eigen::Vector3f &position, float radius, float transparency, float colorR=0.5f, float colorG=0.5f, float colorB=0.5f) |
static SoSeparator * | CreateVerticesVisualization (const std::vector< Eigen::Vector3f > &positions, float radius, VisualizationFactory::Color color=VisualizationFactory::Color::Gray()) |
static void | RemoveDuplicateTextures (SoNode *node, const std::string ¤tPath) |
static SoSeparator * | CreateEllipse (float x, float y, float z, SoMaterial *matBody=NULL, bool showAxes=true, float axesHeight=4.0f, float axesWidth=8.0f, SoMaterial *matAxisX=NULL, SoMaterial *matAxisY=NULL, SoMaterial *matAxisZ=NULL) |
static SoSeparator * | CreateSphere (float radius, float colorR, float colorG, float colorB) |
static SoSeparator * | CreateSphere (const Eigen::Vector3f &p, float radius, float colorR, float colorG, float colorB) |
static SoSeparator * | CreateCylindroid (float axisLengthX, float axisLengthY, float height, SoMaterial *matBody=nullptr) |
static SoSeparator * | Create2DMap (const Eigen::MatrixXf &d, float extendCellX, float extendCellY, const VirtualRobot::ColorMap cm=VirtualRobot::ColorMap(VirtualRobot::ColorMap::eHot), bool drawZeroCells=false, bool drawLines=true) |
static SoSeparator * | Create2DHeightMap (const Eigen::MatrixXf &d, float extendCellX, float extendCellY, float heightZ, const VirtualRobot::ColorMap cm=VirtualRobot::ColorMap(VirtualRobot::ColorMap::eHot), bool drawZeroCells=false, bool drawLines=true) |
static SoSeparator * | CreateOOBBVisualization (const MathTools::OOBB &oobb, Color colorLine=Color::Gray(), float lineSize=4.0f) |
static SoSeparator * | CreateSegmentVisualization (const MathTools::Segment &s, Color colorLine=Color::Gray(), float lineSize=4.0f) |
static SoSeparator * | Colorize (SoNode *model, VisualizationFactory::Color c) |
static SbMatrix | getSbMatrix (const Eigen::Matrix4f &m) |
static SbMatrix | getSbMatrixVec (const Eigen::Vector3f &m) |
static SoSeparator * | CreateGraspSetVisualization (GraspSetPtr graspSet, EndEffectorPtr eef, const Eigen::Matrix4f &pose=Eigen::Matrix4f::Identity(), SceneObject::VisualizationType visu=SceneObject::Full) |
static SoSeparator * | CreateGraspVisualization (GraspPtr grasp, SoSeparator *eefVisu, const Eigen::Matrix4f &pose=Eigen::Matrix4f::Identity()) |
static SoSeparator * | CreateGraspVisualization (GraspPtr grasp, EndEffectorPtr eef, const Eigen::Matrix4f &pose=Eigen::Matrix4f::Identity(), SceneObject::VisualizationType visu=SceneObject::Full) |
static SoSeparator * | CreateEndEffectorVisualization (EndEffectorPtr eef, SceneObject::VisualizationType=SceneObject::Full) |
static SoNode * | getColorNode (Color color) |
static SoSeparator * | CreateText (const std::string &s, float offsetX=20.0f, float offsetY=20.0f, float offsetZ=0.0f) |
static SoSeparator * | CreateBillboardText (const std::string &s, float offsetX=20.0f, float offsetY=20.0f, float offsetZ=0.0f) |
static SoNode * | getCoinVisualization (RobotPtr robot, SceneObject::VisualizationType visuType, bool selectable=true) |
static SoNode * | getCoinVisualization (SceneObjectPtr object, SceneObject::VisualizationType visuType) |
static SoNode * | getCoinVisualization (VirtualRobot::EndEffector::ContactInfoVector &contacts, float frictionConeHeight=30.0f, float frictionConeRadius=15.0f, bool scaleAccordingToApproachDir=true) |
static SoNode * | getCoinVisualization (EndEffector::ContactInfo &contact, float frictionConeHeight=30.0f, float frictionConeRadius=15.0f, bool scaleAccordingToApproachDir=true) |
static SoNode * | getCoinVisualization (VisualizationNodePtr visu) |
static SoNode * | getCoinVisualization (TriMeshModelPtr model) |
static SoNode * | getCoinVisualization (TriMeshModelPtr model, bool shownormals, VisualizationFactory::Color color=VisualizationFactory::Color::Gray(), bool showLines=true) |
static SoNode * | getCoinVisualization (TrajectoryPtr t, Color colorNode=Color::Blue(), Color colorLine=Color::Gray(), float nodeSize=15.0f, float lineSize=4.0f) |
static SoNode * | getCoinVisualization (WorkspaceRepresentationPtr reachSpace, const VirtualRobot::ColorMap cm, bool transformToGlobalPose=true, float maxZGlobal=1e10, float minAngle=-M_PI, float maxAngle=M_PI) |
static SoNode * | getCoinVisualization (WorkspaceRepresentationPtr reachSpace, VirtualRobot::ColorMap cm, const Eigen::Vector3f &axis, bool transformToGlobalPose=true, unsigned char minValue=0, float arrowSize=0, int nrRotations=1) |
static SoNode * | getCoinVisualization (WorkspaceRepresentationPtr reachSpace, const Eigen::Vector3f &fixedEEFOrientationGlobalRPY, VirtualRobot::ColorMap cm=VirtualRobot::ColorMap(VirtualRobot::ColorMap::eHot), bool transformToGlobalPose=true, const Eigen::Vector3f &axis=Eigen::Vector3f(0, 0, 1.0f), unsigned char minValue=0, float arrowSize=0) |
Helper method: Create reach space visualization of a fixed orientation. More... | |
static SoNode * | getCoinVisualization (WorkspaceRepresentationPtr reachSpace, int a, int b, int c, int nrBestEntries, SoSeparator *arrow, const VirtualRobot::ColorMap &cm, bool transformToGlobalPose, unsigned char minValue) |
helper method: create nrBestEntries arrows in direction of maximum orientation for voxelPosition (a,b,c) More... | |
static SoNode * | getCoinVisualization (TSRConstraintPtr constraint, const Color &color) |
static SoNode * | getCoinVisualization (BalanceConstraintPtr constraint, const Color &color) |
static SoNode * | getCoinVisualization (PoseConstraintPtr constraint, const Color &color) |
static SoNode * | getCoinVisualization (PositionConstraintPtr constraint, const Color &color) |
static SoNode * | getCoinVisualization (SupportPolygonPtr supportPolygon, const Color &color) |
static SoMatrixTransform * | getMatrixTransform (const Eigen::Matrix4f &m) |
static SoMatrixTransform * | getMatrixTransformScaleMM2M (const Eigen::Matrix4f &m) |
static SoNode * | createCoinLine (const Eigen::Matrix4f &from, const Eigen::Matrix4f &to, float width, float colorR, float colorG, float colorB) |
static SoNode * | createCoinPartCircle (float radius, float circleCompletion, float width, float colorR, float colorG, float colorB, size_t numberOfCircleParts, float offset=0) |
static SoNode * | getCoinVisualization (WorkspaceGridPtr reachGrid, VirtualRobot::ColorMap cm, bool transformToGlobalPose=true) |
static SoNode * | getCoinVisualization (VirtualRobot::WorkspaceRepresentation::WorkspaceCut2DPtr cutXY, VirtualRobot::ColorMap cm, const Eigen::Vector3f &normal=Eigen::Vector3f::UnitY(), float maxEntry=0.0f, float minAngle=-M_PI, float maxAngle=M_PI) |
static SoOffscreenRenderer * | createOffscreenRenderer (unsigned int width, unsigned int height) |
static bool | renderOffscreen (SoOffscreenRenderer *renderer, RobotNodePtr camNode, SoNode *scene, unsigned char **buffer, float zNear=10.f, float zFar=100000.f, float fov=M_PI/4) |
static bool | renderOffscreenRgbDepthPointcloud (RobotNodePtr camNode, SoNode *scene, short width, short height, bool renderRgbImage, std::vector< unsigned char > &rgbImage, bool renderDepthImgae, std::vector< float > &depthImage, bool renderPointcloud, std::vector< Eigen::Vector3f > &pointCloud, float zNear=10.f, float zFar=100000.f, float vertFov=M_PI/4, float nanValue=NAN) |
Renders the given scene from the given cam position and outputs (optionally) the rgb image, depth image and point cloud. More... | |
static bool | renderOffscreenRgbDepthPointcloud (SoOffscreenRenderer *renderer, RobotNodePtr camNode, SoNode *scene, short width, short height, bool renderRgbImage, std::vector< unsigned char > &rgbImage, bool renderDepthImage, std::vector< float > &depthImage, bool renderPointcloud, std::vector< Eigen::Vector3f > &pointCloud, float zNear=10.f, float zFar=100000.f, float vertFov=M_PI/4, float nanValue=NAN) |
Renders the given scene from the given cam position and outputs (optionally) the rgb image, depth image and point cloud. This version is much faster if always the same SoOffscreenRenderer is passed in. More... | |
static bool | renderOffscreenRgbDepthPointcloud (SoOffscreenRenderer *renderer, const Eigen::Matrix4f camPose, SoNode *scene, short width, short height, bool renderRgbImage, std::vector< unsigned char > &rgbImage, bool renderDepthImage, std::vector< float > &depthImage, bool renderPointcloud, std::vector< Eigen::Vector3f > &pointCloud, float zNear=10.f, float zFar=100000.f, float vertFov=M_PI/4, float nanValue=NAN) |
static bool | renderOffscreenRgbDepthPointcloud (RobotNodePtr camNode, SoNode *scene, short width, short height, std::vector< unsigned char > &rgbImage, std::vector< float > &depthImage, std::vector< Eigen::Vector3f > &pointCloud, float zNear=10.f, float zFar=100000.f, float vertFov=M_PI/4, float nanValue=NAN) |
Renders the given scene from the given cam position and outputs the rgb image, depth image and point cloud. More... | |
static bool | renderOffscreen (SoOffscreenRenderer *renderer, SoPerspectiveCamera *cam, SoNode *scene, unsigned char **buffer) |
static SoGroup * | convertSoFileChildren (SoGroup *orig) |
static SoNode * | copyNode (SoNode *n) |
static std::string | getName () |
static std::shared_ptr< VisualizationFactory > | createInstance (void *) |
![]() | |
static std::shared_ptr< VisualizationFactory > | fromName (const std::string &name, void * params) |
static std::shared_ptr< VisualizationFactory > | first (void * params) |
static std::string | getName () |
static std::shared_ptr< VisualizationFactory > | createInstance (void *) |
static void | registerClass (const std::string &name, initialisationFunction init) |
static std::vector< std::string > | getSubclassList () |
Static Protected Member Functions | |
static SoNode * | GetNodeFromPrimitive (Primitive::PrimitivePtr primitive, bool boundingBox, Color color) |
static void | GetVisualizationFromSoInput (SoInput &soInput, VisualizationNodePtr &visualizationNode, bool bbox=false, bool freeDuplicateTextures=true) |
static char | IVToolsHelper_ReplaceSpaceWithUnderscore (char input) |
A Coin3D based implementation of a VisualizationFactory.
typedef std::map<std::pair<size_t, std::string>, void*> VirtualRobot::CoinVisualizationFactory::TextureCacheMap |
|
default |
|
overridedefault |
|
overridevirtual |
Move local visualization by homogeneous matrix m. MM is used.
Reimplemented from VirtualRobot::VisualizationFactory.
|
overridevirtual |
Here, a manual cleanup can be called, no Coin3D access possible after this. Usually no need to call cleanup explicitly, since cleanup is performed automatically at application exit.
Reimplemented from VirtualRobot::VisualizationFactory.
|
static |
Creates a colored model, by creating a new SoSeparator and adding a basecolor with overide flags followed by the model.
|
static |
When SoFiles are used, Coin3D just stores references to files instead of the real contents. This may cause problems when saving an inventor file. With this method, a group node can be converted in order to ensure that all potential files are loaded and added to the group.
|
static |
|
static |
|
static |
|
overridevirtual |
Reimplemented from VirtualRobot::VisualizationFactory.
|
static |
|
static |
|
static |
|
static |
Billboard Text visu. Offsets in mm.
|
overridevirtual |
Reimplemented from VirtualRobot::VisualizationFactory.
|
static |
|
overridevirtual |
A box, dimensions are given in mm.
Reimplemented from VirtualRobot::VisualizationFactory.
|
overridevirtual |
Reimplemented from VirtualRobot::VisualizationFactory.
|
overridevirtual |
Reimplemented from VirtualRobot::VisualizationFactory.
|
static |
|
static |
|
static |
|
overridevirtual |
Reimplemented from VirtualRobot::VisualizationFactory.
|
static |
|
overridevirtual |
Reimplemented from VirtualRobot::VisualizationFactory.
|
static |
|
overridevirtual |
Creates an coordinate axis aligned ellipse
x | The extend in x direction must be >= 1e-6 |
y | The extend in y direction must be >= 1e-6 |
z | The extend in z direction must be >= 1e-6 |
showAxes | If true, the axes are visualized |
axesHeight | The height of the axes (measured from the body surface) |
axesWidth | The width of the axes. |
Reimplemented from VirtualRobot::VisualizationFactory.
|
static |
Creates an coordinate axis aligned ellipse
x | The extend in x direction must be >= 1e-6 |
y | The extend in y direction must be >= 1e-6 |
z | The extend in z direction must be >= 1e-6 |
matBody | If not given a standard material is used for the ellipse body |
showAxes | If true, the axes are visualized |
axesHeight | The height of the axes (measured from the body surface) |
axesWidth | The width of the axes. |
matAxisX | If not given a standard material is used for axis X |
matAxisY | If not given a standard material is used for axis Y |
matAxisZ | If not given a standard material is used for axis Z |
|
static |
Create a visualization of the end effector. The visualization is moved, so that the origin is identical with the coordinate system of the TCP.
|
static |
Create a visualization of a set of grasps.
graspSet | The grasps to visualize |
eef | The visualization of this eef is used to visualize the grasps |
pose | The grasp set is visualized relatively to this pose (e.g. use the object position here) |
visu | The visualization type of the EEFs. |
|
static |
|
static |
|
static |
|
static |
|
overridevirtual |
Reimplemented from VirtualRobot::VisualizationFactory.
|
overridevirtual |
Reimplemented from VirtualRobot::VisualizationFactory.
|
static |
Create an offscreen renderer object with the given width and height.
|
static |
|
overridevirtual |
Reimplemented from VirtualRobot::VisualizationFactory.
|
static |
|
static |
|
static |
|
static |
|
static |
|
static |
|
overridevirtual |
Reimplemented from VirtualRobot::VisualizationFactory.
|
static |
|
static |
|
overridevirtual |
Reimplemented from VirtualRobot::VisualizationFactory.
|
static |
Text visu. Offsets in mm.
|
overridevirtual |
Reimplemented from VirtualRobot::VisualizationFactory.
|
overridevirtual |
Reimplemented from VirtualRobot::VisualizationFactory.
|
overridevirtual |
Reimplemented from VirtualRobot::VisualizationFactory.
|
overridevirtual |
Reimplemented from VirtualRobot::VisualizationFactory.
|
overridevirtual |
Create a united visualization. Internally all visualizations are copied and added to one SoSeparator. All visualizations have to be of type CoinVisualizationNode.
Reimplemented from VirtualRobot::VisualizationFactory.
|
overridevirtual |
Reimplemented from VirtualRobot::VisualizationFactory.
|
static |
|
static |
|
overridevirtual |
Create an empty VisualizationNode.
Reimplemented from VirtualRobot::VisualizationFactory.
|
static |
Convenient method to retrieve a coin visualization for a robot
|
static |
Convenient method to retrieve a coin visualization for a SceneObject/Obstacle/ManipulationObject
|
static |
Convenient method to retrieve a coin visualization for a set of contacts.
contacts | The contacts to be visualized |
frictionConeHeight | The height of the friction cone [mm]. |
frictionConeRadius | The radius of the cone [mm]. |
scaleAccordingToApproachDir | If true, the parallel component of the contact normal is computed according to the approahcDirection of the contact. |
|
static |
Convenient method to retrieve a coin visualization for a contact.
contact | The contact to be visualized |
frictionConeHeight | The height of the friction cone [mm]. |
frictionConeRadius | The radius of the cone [mm]. |
scaleAccordingToApproachDir | If true, the parallel component of the contact normal is computed according to the approahcDirection of the contact. |
|
static |
|
static |
|
static |
|
static |
|
static |
Create a visualization of the reachability data.
|
static |
Creates a visualization of the reachability data. For each 3D point, the orientation with maximum entry is determined and visualized as an arrow. The direction of this arrow is aligned to the param axis.
|
static |
Helper method: Create reach space visualization of a fixed orientation.
|
static |
helper method: create nrBestEntries arrows in direction of maximum orientation for voxelPosition (a,b,c)
|
static |
|
static |
|
static |
|
static |
|
static |
|
static |
Creates a visualization of the reachability grid.
|
static |
Create quads according to cutXY plane. Normal can be UnitX, UnitY or UnitZ.
maxEntry | If 0 the maximal entry of the cut plane is used as refernce. |
|
static |
Creates a material node.
|
static |
Create a SoMatrixTransform from the given pose
m | The pose with translation given in meter. |
|
static |
Create a SoMatrixTransform from the given pose Converts the pose from MM to M (scales by 0.001)
m | The pose with translation given in millimeter. |
|
static |
|
staticprotected |
|
static |
|
static |
|
virtual |
|
virtual |
|
virtual |
|
overridevirtual |
This method creates a VirtualRobot::CoinVisualizationNode from a given filename
. An instance of VirtualRobot::VisualizationNode is returned in case of an occured error.
filename | file to load the Coin3D visualization from. |
boundingBox | Use bounding box instead of full model. |
Reimplemented from VirtualRobot::VisualizationFactory.
|
overridevirtual |
Reimplemented from VirtualRobot::VisualizationFactory.
|
virtual |
|
overridevirtual |
This method creates a VirtualRobot::CoinVisualizationNode from a given vector of primitives
. An instance of VirtualRobot::VisualizationNode is returned in case of an occured error.
primitives | vector of primitives to create the visualization from. |
boundingBox | Use bounding box instead of full model. |
Reimplemented from VirtualRobot::VisualizationFactory.
|
staticprotected |
This method reads the data from the given soInput
and creates a new CoinVisualizationNode with the read Coin model if no error occurred during reading the model. The newly created CoinVisualizationNode is then stored in visualisationNode
.
soInput | SoInput instance from which the model is read. |
visualizationNode | VisualizationNodePtr instance in which the created CoinVisualizationNode is stored. |
boundingBox | Use bounding box instead of full model. |
|
virtual |
This method creates a VirtualRobot::CoinVisualizationNode from a given modelString
. An instance of VirtualRobot::VisualizationNode is returned in case of an occured error.
modelString | string to load the Coin3D visualization from. |
boundingBox | Use bounding box instead of full model. |
|
overridevirtual |
Initialises SoDB and SoQt. Sets the COIN_SEPARATE_DIFFUSE_TRANSPARENCY_OVERRIDE environment variable to enable a Coin3D transparency extension.
Reimplemented from VirtualRobot::VisualizationFactory.
|
inlinestaticprotected |
|
static |
|
static |
The cam node has to be oriented as follows: The camera is pointing along the positive z axis and the positive x axis is pointing upwards.
renderer | The renderer should have been created with the createOffscreenRenderer method |
camNode | The node of the robot that defines the position of the camera. Any node of the robot can host a camera. |
scene | The scene that should be rendered. |
buffer | The result is stored here. The origin of the 2D image is at the left bottom! The resulting buffer has the size width*height*3, with the extends as defined in the createOffscreenRenderer method. |
zNear | The near plane's distance. |
zFar | The far plane's distance |
fov | The fov in rad. (vertical) |
|
static |
Use a custom camera for rendering
renderer | The renderer should have been created with the createOffscreenRenderer method |
cam | The camera. |
scene | The scene that should be rendered. |
buffer | The result is stored here. The origin of the 2D image is at the left bottom! The resulting buffer has the size width*height*3, with the extends as defined in the createOffscreenRenderer method. |
|
static |
Renders the given scene from the given cam position and outputs (optionally) the rgb image, depth image and point cloud.
camNode | The node of the robot that defines the position of the camera. Any node of the robot can host a camera. |
scene | The scene that should be rendered. |
width | The used image width. (>0) |
height | The used image height. (>0) |
renderRgbImage | Whether to output the rgb image. |
rgbImage | The rgb image's output parameter. |
renderDepthImgae | Whether to output the depth image. |
depthImage | The depth image's output parameter. |
renderPointcloud | Whether to output the point cloud. |
pointCloud | The pointcloud's output parameter. |
zNear | The near plane's distance. |
zFar | The far plane's distance |
vertFov | The fov in rad. (vertical) |
nanValue | All values above the zFar value will be mapped on this value (usually nan or 0) |
|
static |
Renders the given scene from the given cam position and outputs (optionally) the rgb image, depth image and point cloud. This version is much faster if always the same SoOffscreenRenderer is passed in.
camNode | The node of the robot that defines the position of the camera. Any node of the robot can host a camera. |
scene | The scene that should be rendered. |
width | The used image width. (>0) |
height | The used image height. (>0) |
renderRgbImage | Whether to output the rgb image. |
rgbImage | The rgb image's output parameter. |
renderDepthImgae | Whether to output the depth image. |
depthImage | The depth image's output parameter. |
renderPointcloud | Whether to output the point cloud. |
pointCloud | The pointcloud's output parameter. |
zNear | The near plane's distance. |
zFar | The far plane's distance |
vertFov | The fov in rad. (vertical) |
nanValue | All values above the zFar value will be mapped on this value (usually nan or 0) |
|
static |
TODO find way to only render rgb once
|
inlinestatic |
Renders the given scene from the given cam position and outputs the rgb image, depth image and point cloud.
camNode | The node of the robot that defines the position of the camera. Any node of the robot can host a camera. |
scene | The scene that should be rendered. |
width | The used image width. (>0) |
height | The used image height. (>0) |
renderRgbImage | Whether to output the rgb image. |
rgbImage | The rgb image's output parameter. |
renderDepthImgae | Whether to output the depth image. |
depthImage | The depth image's output parameter. |
renderPointcloud | Whether to output the point cloud. |
pointCloud | The pointcloud's output parameter. |
zNear | The near plane's distance. |
zFar | The far plane's distance |
vertFov | The fov in rad. (vertical) |
nanValue | All values above the zFar value will be mapped on this value (usually nan or 0) |