tesseract_robotics.tesseract_geometry¶
This module contains the geometry data structures for Tesseract. The user dose not typically need to use these classes since they are loaded from URDF. However, they are available for use for purposes such as dynamically modifying the environment using “Environment Commands”.
Classes¶
Box Class¶
- class tesseract_robotics.tesseract_geometry.Box(*args)
- clone()
Create a copy of this shape
Capsule Class¶
- class tesseract_robotics.tesseract_geometry.Capsule(*args)
- clone()
Create a copy of this shape
Cone Class¶
- class tesseract_robotics.tesseract_geometry.Cone(*args)
- clone()
Create a copy of this shape
ConvexMesh Class¶
- class tesseract_robotics.tesseract_geometry.ConvexMesh(*args)
- clone()
Create a copy of this shape
- getCreationMethod()
Get how the convex hull was created Notes: This used when writing back out to urdf
- Return type:
int
- Returns:
The CreationMethod
- setCreationMethod(method)
Set the method used to create the convex mesh Notes: This used when writing back out to urdf
- Parameters:
value – The CreationMethod
Cylinder Class¶
- class tesseract_robotics.tesseract_geometry.Cylinder(*args)
- clone()
Create a copy of this shape
Geometry Class¶
- class tesseract_robotics.tesseract_geometry.Geometry(*args, **kwargs)
- clone()
Create a copy of this shape
Mesh Class¶
- class tesseract_robotics.tesseract_geometry.Mesh(*args)
- clone()
Create a copy of this shape
MeshMaterial Class¶
- class tesseract_robotics.tesseract_geometry.MeshMaterial(*args)
Represents material information extracted from a mesh file
Mesh files contain material information. The mesh parser will extract the material information and store it in a MeshMaterial instance. The MeshMaterial class uses a subset PBR Metallic workflow, as specified in the glTF 2.0 file format standard. The four parameters supported are baseColorFactor, metallicFactor, roughnessFactor, and emmisiveFactor. (The MeshTexture class stores diffuse textures that can be used for decals and fiducial marks, and is stored separately from MeshMaterial.) These four parameters and MeshTexture should be enough to display “CAD quality” renderings in visualizers. The full mesh file should be used when higher quality rendering is required.
The MeshMaterial favors PBR materials extracted from glTF 2.0 files. COLLADA does not support PBR. Only “Diffuse” and “Emissive” are read. “Specular” and “Ambient” are ignored.
- getBaseColorFactor()
Get the base color of the mesh
- Return type:
Eigen::Vector4d
- Returns:
The base color in RGBA
- getEmissiveFactor()
Get the emissive factor of the mesh
“Emissive factor” is used to make the mesh “glow”. How this is interpreted depends on the rendering engine.
- Return type:
Eigen::Vector4d
- Returns:
The emissive factor in RGBA
- getMetallicFactor()
Get the Metallic Factor of the mesh (PBR parameter)
- Return type:
float
- Returns:
The metallic factor, between 0 and 1
- getRoughnessFactor()
Get the Roughness Factor of the mesh (PBR parameter)
- Return type:
float
- Returns:
The roughness factor, between 0 and 1
MeshTexture Class¶
- class tesseract_robotics.tesseract_geometry.MeshTexture(texture_image, uvs)
Represents a texture and UV coordinates extracted from a mesh file
Mesh files contain (or reference) image files that form textures on the surface of the mesh. UV coordinates specify how the image is applied to the mesh. The MeshTexture structure contains a resource to the image, and the UV coordinates. Currently only jpg and png image formats are supported.
UV coordinates specify the location of each vertex in the mesh on the texture. Each (u,v) coordinate is normalized to be between 0 and 1.
- getTextureImage()
Get the texture image
Must be jpg or png
- Return type:
Resource
- Returns:
Resource to the texture image
- getUVs()
Get the texture UV coordinates
- Return type:
std::shared_ptr< tesseract_common::VectorVector2d const >
- Returns:
UV coordinate vector
OcTree Class¶
- class tesseract_robotics.tesseract_geometry.OcTree(*args, **kwargs)
Octree Class¶
- class tesseract_robotics.tesseract_geometry.Octree(*args)
- calcNumSubShapes()
Calculate the number of sub shapes that would get generated for this octree
This is expensive and should not be called multiple times
- Return type:
int
- Returns:
number of sub shapes
- clone()
Create a copy of this shape
- static prune(octree)
A custom octree prune which will prune if all children are above the occupancy threshold.
This is different from the octomap::OcTree::prune which requires all children to have the same occupancy to be collapsed.
- Parameters:
octree (
OcTree
) – The octree to be pruned.
- update()
Octrees are typically generated from 3D sensor data so this method should be used to efficiently update the collision shape.
Plane Class¶
- class tesseract_robotics.tesseract_geometry.Plane(*args)
- clone()
Create a copy of this shape
PolygonMesh Class¶
- class tesseract_robotics.tesseract_geometry.PolygonMesh(*args)
- clone()
Create a copy of this shape
- getFaceCount()
Get face count
- Return type:
int
- Returns:
Number of faces
- getFaces()
Get Polygon mesh faces
- Return type:
std::shared_ptr< Eigen::VectorXi const >
- Returns:
A vector of face indices
- getMaterial()
Get material data extracted from the mesh file
Mesh files contain material information. The mesh parser will extract the material information and store it in a MeshMaterial structure.
- Return type:
MeshMaterial
- Returns:
The MeshMaterial data extracted from mesh file
- getNormals()
Get the vertex normal vectors
Optional, may be nullptr
- Return type:
std::shared_ptr< tesseract_common::VectorVector3d const >
- Returns:
The vertex normal vector
- getResource()
Get the path to file used to generate the mesh
Note: If empty, assume it was manually generated.
- Return type:
Resource
- Returns:
Absolute path to the mesh file
- getScale()
Get the scale applied to file used to generate the mesh
- Return type:
Eigen::Vector3d
- Returns:
The scale x, y, z
- getTextures()
Get textures extracted from the mesh file
Mesh files contain (or reference) image files that form textures on the surface of the mesh. UV coordinates specify how the image is applied to the mesh. The MeshTexture structure contains a resource to the image, and the UV coordinates. Currently only jpg and png image formats are supported.
- Return type:
std::shared_ptr< std::vector< tesseract_geometry::MeshTexture::Ptr,std::allocator< tesseract_geometry::MeshTexture::Ptr > > const >
- Returns:
Vector of mesh textures
- getVertexColors()
Get the vertex colors
Optional, may be nullptr
- Return type:
std::shared_ptr< tesseract_common::VectorVector4d const >
- Returns:
Vertex colors
- getVertexCount()
Get vertex count
- Return type:
int
- Returns:
Number of vertices
- getVertices()
Get Polygon mesh vertices
- Return type:
std::shared_ptr< tesseract_common::VectorVector3d const >
- Returns:
A vector of vertices
SDFMesh Class¶
- class tesseract_robotics.tesseract_geometry.SDFMesh(*args)
- clone()
Create a copy of this shape
Sphere Class¶
- class tesseract_robotics.tesseract_geometry.Sphere(*args)
- clone()
Create a copy of this shape
Functions¶
createConvexMeshFromBytes Function¶
- tesseract_robotics.tesseract_geometry.createConvexMeshFromBytes(*args)
Create a mesh from byte array
- Parameters:
url (string) – The URL of source resource
bytes (uint8_t) – Byte array
bytes_len (int) – The length of bytes
scale (Eigen::Vector3d, optional) – Perform an axis scaling
triangulate (boolean, optional) – If true the mesh will be triangulated. This should be done for visual meshes. In the case of collision meshes do not triangulate convex hull meshes.
flatten (boolean, optional) – If true all meshes will be condensed into a single mesh. This should only be used for visual meshes, do not flatten collision meshes.
normals (boolean, optional) – If true, loads mesh normals
vertex_colors (boolean, optional) – If true, loads mesh vertex colors
material_and_texture (boolean, optional) – If true, loads mesh materials and textures
- Return type:
std::vector< std::shared_ptr< tesseract_geometry::ConvexMesh >,std::allocator< std::shared_ptr< tesseract_geometry::ConvexMesh > > >
- Returns:
createConvexMeshFromPath Function¶
- tesseract_robotics.tesseract_geometry.createConvexMeshFromPath(*args)
Create a mesh using assimp from file path
- Parameters:
path (string) – The file path to the mesh
scale (Eigen::Vector3d, optional) – Perform an axis scaling
triangulate (boolean, optional) – If true the mesh will be triangulated. This should be done for visual meshes. In the case of collision meshes do not triangulate convex hull meshes.
flatten (boolean, optional) – If true all meshes will be condensed into a single mesh. This should only be used for visual meshes, do not flatten collision meshes.
normals (boolean, optional) – If true, loads mesh normals
vertex_colors (boolean, optional) – If true, loads mesh vertex colors
material_and_texture (boolean, optional) – If true, loads mesh materials and textures
- Return type:
std::vector< std::shared_ptr< tesseract_geometry::ConvexMesh >,std::allocator< std::shared_ptr< tesseract_geometry::ConvexMesh > > >
- Returns:
createConvexMeshFromResource Function¶
- tesseract_robotics.tesseract_geometry.createConvexMeshFromResource(*args)
Create a mesh using assimp from resource
- Parameters:
resource (
Resource
) – The located resourcescale (Eigen::Vector3d, optional) – Perform an axis scaling
triangulate (boolean, optional) – If true the mesh will be triangulated. This should be done for visual meshes. In the case of collision meshes do not triangulate convex hull meshes.
flatten (boolean, optional) – If true all meshes will be condensed into a single mesh. This should only be used for visual meshes, do not flatten collision meshes.
normals (boolean, optional) – If true, loads mesh normals
vertex_colors (boolean, optional) – If true, loads mesh vertex colors
material_and_texture (boolean, optional) – If true, loads mesh materials and textures
- Return type:
std::vector< std::shared_ptr< tesseract_geometry::ConvexMesh >,std::allocator< std::shared_ptr< tesseract_geometry::ConvexMesh > > >
- Returns:
createMeshFromBytes Function¶
- tesseract_robotics.tesseract_geometry.createMeshFromBytes(*args)
Create a mesh from byte array
- Parameters:
url (string) – The URL of source resource
bytes (uint8_t) – Byte array
bytes_len (int) – The length of bytes
scale (Eigen::Vector3d, optional) – Perform an axis scaling
triangulate (boolean, optional) – If true the mesh will be triangulated. This should be done for visual meshes. In the case of collision meshes do not triangulate convex hull meshes.
flatten (boolean, optional) – If true all meshes will be condensed into a single mesh. This should only be used for visual meshes, do not flatten collision meshes.
normals (boolean, optional) – If true, loads mesh normals
vertex_colors (boolean, optional) – If true, loads mesh vertex colors
material_and_texture (boolean, optional) – If true, loads mesh materials and textures
- Return type:
std::vector< std::shared_ptr< tesseract_geometry::Mesh >,std::allocator< std::shared_ptr< tesseract_geometry::Mesh > > >
- Returns:
createMeshFromPath Function¶
- tesseract_robotics.tesseract_geometry.createMeshFromPath(*args)
Create a mesh using assimp from file path
- Parameters:
path (string) – The file path to the mesh
scale (Eigen::Vector3d, optional) – Perform an axis scaling
triangulate (boolean, optional) – If true the mesh will be triangulated. This should be done for visual meshes. In the case of collision meshes do not triangulate convex hull meshes.
flatten (boolean, optional) – If true all meshes will be condensed into a single mesh. This should only be used for visual meshes, do not flatten collision meshes.
normals (boolean, optional) – If true, loads mesh normals
vertex_colors (boolean, optional) – If true, loads mesh vertex colors
material_and_texture (boolean, optional) – If true, loads mesh materials and textures
- Return type:
std::vector< std::shared_ptr< tesseract_geometry::Mesh >,std::allocator< std::shared_ptr< tesseract_geometry::Mesh > > >
- Returns:
createMeshFromResource Function¶
- tesseract_robotics.tesseract_geometry.createMeshFromResource(*args)
Create a mesh using assimp from resource
- Parameters:
resource (
Resource
) – The located resourcescale (Eigen::Vector3d, optional) – Perform an axis scaling
triangulate (boolean, optional) – If true the mesh will be triangulated. This should be done for visual meshes. In the case of collision meshes do not triangulate convex hull meshes.
flatten (boolean, optional) – If true all meshes will be condensed into a single mesh. This should only be used for visual meshes, do not flatten collision meshes.
normals (boolean, optional) – If true, loads mesh normals
vertex_colors (boolean, optional) – If true, loads mesh vertex colors
material_and_texture (boolean, optional) – If true, loads mesh materials and textures
- Return type:
std::vector< std::shared_ptr< tesseract_geometry::Mesh >,std::allocator< std::shared_ptr< tesseract_geometry::Mesh > > >
- Returns:
createSDFMeshFromBytes Function¶
- tesseract_robotics.tesseract_geometry.createSDFMeshFromBytes(*args)
Create a mesh from byte array
- Parameters:
url (string) – The URL of source resource
bytes (uint8_t) – Byte array
bytes_len (int) – The length of bytes
scale (Eigen::Vector3d, optional) – Perform an axis scaling
triangulate (boolean, optional) – If true the mesh will be triangulated. This should be done for visual meshes. In the case of collision meshes do not triangulate convex hull meshes.
flatten (boolean, optional) – If true all meshes will be condensed into a single mesh. This should only be used for visual meshes, do not flatten collision meshes.
normals (boolean, optional) – If true, loads mesh normals
vertex_colors (boolean, optional) – If true, loads mesh vertex colors
material_and_texture (boolean, optional) – If true, loads mesh materials and textures
- Return type:
std::vector< std::shared_ptr< tesseract_geometry::SDFMesh >,std::allocator< std::shared_ptr< tesseract_geometry::SDFMesh > > >
- Returns:
createSDFMeshFromPath Function¶
- tesseract_robotics.tesseract_geometry.createSDFMeshFromPath(*args)
Create a mesh using assimp from file path
- Parameters:
path (string) – The file path to the mesh
scale (Eigen::Vector3d, optional) – Perform an axis scaling
triangulate (boolean, optional) – If true the mesh will be triangulated. This should be done for visual meshes. In the case of collision meshes do not triangulate convex hull meshes.
flatten (boolean, optional) – If true all meshes will be condensed into a single mesh. This should only be used for visual meshes, do not flatten collision meshes.
normals (boolean, optional) – If true, loads mesh normals
vertex_colors (boolean, optional) – If true, loads mesh vertex colors
material_and_texture (boolean, optional) – If true, loads mesh materials and textures
- Return type:
std::vector< std::shared_ptr< tesseract_geometry::SDFMesh >,std::allocator< std::shared_ptr< tesseract_geometry::SDFMesh > > >
- Returns:
createSDFMeshFromResource Function¶
- tesseract_robotics.tesseract_geometry.createSDFMeshFromResource(*args)
Create a mesh using assimp from resource
- Parameters:
resource (
Resource
) – The located resourcescale (Eigen::Vector3d, optional) – Perform an axis scaling
triangulate (boolean, optional) – If true the mesh will be triangulated. This should be done for visual meshes. In the case of collision meshes do not triangulate convex hull meshes.
flatten (boolean, optional) – If true all meshes will be condensed into a single mesh. This should only be used for visual meshes, do not flatten collision meshes.
normals (boolean, optional) – If true, loads mesh normals
vertex_colors (boolean, optional) – If true, loads mesh vertex colors
material_and_texture (boolean, optional) – If true, loads mesh materials and textures
- Return type:
std::vector< std::shared_ptr< tesseract_geometry::SDFMesh >,std::allocator< std::shared_ptr< tesseract_geometry::SDFMesh > > >
- Returns:
isIdentical Function¶
- tesseract_robotics.tesseract_geometry.isIdentical(geom1, geom2)
Check if two Geometries are identical
- Parameters:
geom1 (
Geometry
) – First Geometrygeom2 (
Geometry
) – Second Geometry
- Return type:
boolean
- Returns:
True if identical, otherwise false
Constants¶
CONVEX_MESH
POLYGON_MESH
SDF_MESH
SPHERE_INSIDE
SPHERE_OUTSIDE
Container Templates¶
ConvexMeshVector
->std::vector<std::shared_ptr<tesseract_geometry::ConvexMesh> >
Geometries
->std::vector<std::shared_ptr<tesseract_geometry::Geometry> >
GeometriesConst
->std::vector<std::shared_ptr<const tesseract_geometry::Geometry> >
MeshVector
->std::vector<std::shared_ptr<tesseract_geometry::Mesh> >
PolygonMeshVector
->std::vector<std::shared_ptr<tesseract_geometry::PolygonMesh> >
SDFMeshVector
->std::vector<std::shared_ptr<tesseract_geometry::SDFMesh> >
VectorMeshTexture
->std::vector<std::shared_ptr<tesseract_geometry::MeshTexture>>