vhacdOptions
Description
The vhacdOptions
object defines voxelized hierarchical approximate
convex decomposition (V-HACD) solver options for functions such as collisionVHACD
and
importrobot
. To decompose individual concave
meshes into convex meshes for collision checking, use vhacdOptions
with the
Type
property set to "IndividualMesh"
. To decompose
the meshes of a rigid body tree, use vhacdOptions
with the
Type
property set to "RigidBodyTree"
.
Creation
Description
OPTS = vhacdOptions
creates a V-HACD solver options object with
default property values for decomposing individual meshes with the collisionVHACD
function.
OPTS = vhacdOptions(
specifies the
type of decomposition. Use this syntax to create V-HACD solver options with the
Type
)Type
property set to "RigidBodyTree"
for use
with the importrobot
function.
Note
If you set only the Type
property at object construction,
then the properties use the default values for the corresponding decomposition
type.
OPTS = vhacdOptions(
sets properties using one or more name-value arguments.Type
,Name=Value
)
Properties
Type
— Type of decomposition
"IndividualMesh"
(default) | "RigidBodyTree"
Type of decomposition, specified as "IndividualMesh"
or
"RigidBodyTree"
. To decompose a single mesh using the collisionVHACD
function, set Type
to
"IndividualMesh"
. To decompose robot models during import with the
importrobot
function, set
Type
to "RigidBodyTree"
.
The default values of the VoxelResolution
,
MaxNumConvexHulls
, and MaxNumVerticesPerHull
properties depend on the specified Type
.
Data Types: char
| string
VoxelResolution
— Voxel resolution of decomposition
128000
(default) | positive integer | N-element vector of positive integers
Voxel resolution of the decomposition, specified as a positive integer or an
N-element vector of positive integers. N is the
number of rigid bodies on the rigid body tree model specified in the importrobot
function. Using a higher voxel resolution can improve the
accuracy of the decomposition at the cost of increasing the decomposition time.
If you set the Type
property to
"RigidBodyTree"
at object construction, the default value of
VoxelResolution
is 2000
for all bodies of the
rigid body tree. To set one voxel resolution for all rigid bodies of the rigid body
tree, specify VoxelResolution
as a positive integer. To
individually specify voxel resolutions for each body of the rigid body tree, specify
VoxelResolution
as an N-element vector of
positive integers.
MaxNumConvexHulls
— Maximum number of convex hulls
32
(default) | positive integer | N-element vector of positive integers
Maximum number of convex hulls after decomposition, specified as a positive integer
or an N-element vector of positive integers. N is
the number of rigid bodies on the rigid body tree model specified in the importrobot
function. Increasing the number of convex hulls can improve
the accuracy of the decomposition, but may also result in an increase in the number of
convex meshes produced by the decomposition. More meshes can generate more accurate
results at the cost of a longer collision-checking time.
If you set the Type
property to
"RigidBodyTree"
at object construction, the default value of
MaxNumConvexHulls
is 8
for all bodies of the
rigid body tree. To set one voxel resolution for all rigid bodies of the rigid body
tree, specify MaxNumConvexHulls
as a positive integer. To
individually specify voxel resolutions for each body, specify
MaxNumConvexHulls
as an N-element vector of
positive integers.
MaxNumVerticesPerHull
— Maximum number of vertices per convex hull
128
(default) | positive integer | N-element vector of positive integers
Maximum number of vertices per convex hull after decomposition, specified as a
positive integer or an N-element vector of positive integers.
N is the number of rigid bodies on the rigid body tree model
specified in the importrobot
function. Increasing the
maximum number of vertices per convex hull can improve the accuracy of each convex hull
at the cost of a longer decomposition time.
If you set the Type
property to
"RigidBodyTree"
at object construction, the default value of
MaxNumVerticesPerHull
is 16
for all bodies of
the rigid body tree. To set one voxel resolution for all rigid bodies of the rigid body
tree, specify MaxNumVerticesPerHull
as a positive integer. To
specify a voxel resolution for each body, specify
MaxNumVerticesPerHull
as an N-element vector
of positive integers.
FillMode
— Fill mode for interior voxels of mesh
"FLOOD_FILL"
(default) | "RAYCAST_FILL"
| "SURFACE_ONLY"
Fill mode for interior voxels of the mesh after voxelization, specified as
"FLOOD_FILL"
, "SURFACE_ONLY"
, or
"RAYCAST_FILL"
:
"FLOOD_FILL"
— The flood-fill mode uses the flood-fill algorithm to determine the outer surface of the mesh. After determining the outer surface of the mesh, the V-HACD solver fills interior voxels enclosed by the outer surface."FLOOD_FILL"
mode produces the most accurate result for closed meshes. If you use flood fill mode for an open mesh, the flood fill algorithm considers the inner surface of the mesh as connected to the outer surface of the mesh, resulting in a hollow mesh. If the mesh is open, use"RAYCAST_FILL"
mode for better results."RAYCAST_FILL"
— Raycasting fill mode uses raycasting to identify the outer surface of the mesh and fill the interior voxels enclosed by the outer surface of the mesh. Use this mode to fill interior voxels of open meshes. For better accuracy, use 3-D modeling software to close the mesh and use the"FLOOD_FILL"
mode."SURFACE_ONLY"
— Surface-only fill mode does not fill any interior voxels in the mesh. Use this mode for meshes that should have no volume.
Data Types: char
| string
SourceMesh
— Source mesh type of imported rigid body tree to decompose
"CollisionGeometry"
(default) | "VisualGeometry"
Source mesh type of the rigid body tree to decompose when using the importrobot
function, specified as "CollisionGeometry"
or "VisualGeometry"
:
"CollisionGeometry"
— Decompose the collision geometries of the rigid body tree model, which are used for collision checking. Decomposing the collision geometry meshes can lower complexity of the meshes and improve the collision-checking speed at the cost of collision-checking accuracy.This code displays the collision geometries of a robot without the visual geometries:
robot = loadrobot("rethinkSawyer"); show(robot,homeConfiguration(robot),Collisions="on",Visuals="off"); axis auto
"VisualGeometry"
— Decompose the visual geometries of the rigid body tree model, which represent a more accurate visualization of the robot appearance. Decomposing the visual geometries can improve collision-checking accuracy over that provided by the collision geometries.This code displays the visual geometries of a robot without the collision geometries:
robot = loadrobot("rethinkSawyer"); show(robot,homeConfiguration(robot),Collisions="off",Visuals="on"); axis auto
Dependencies
To enable this property, you must set the Type
property to
"RigidBodyTree"
.
Data Types: char
| string
Examples
Replace Rigid Body Collision Meshes with Decompositions of Visual Meshes
Load the Rethink Robotics Sawyer robot.
robot = loadrobot("rethinkSawyer",DataFormat="row")
robot = rigidBodyTree with properties: NumBodies: 20 Bodies: {1x20 cell} Base: [1x1 rigidBody] BodyNames: {1x20 cell} BaseName: 'base' Gravity: [0 0 0] DataFormat: 'row'
Show the robot with just the visual meshes and show the robot with just the collision meshes. Use a vertical view so the difference between the arms is more clear.
tiledlayout(1,2) sgtitle("Rethink Robotics Sawyer") nexttile show(robot,Visuals="on",Collisions="off"); title("Top Down View") axis auto view(90,90) nexttile show(robot,Visuals="off",Collisions="on"); title("Top Down View") axis auto view(90,90)
Note that each body of the arm is represented by a single convex mesh that does not accurately represent the physical boundaries of the arm. To achieve more accurate collision checking, you must decompose the visual meshes of the robot. The rigid body tree stores the rigid bodies of the arm at indices 9
to 17
.
First, create V-HACD solver options for individual mesh decompositions with the maximum number of convex hulls set to 10
.
opts = vhacdOptions("IndividualMesh",MaxNumConvexHulls=10);
Then for each rigid body:
Get the current rigid body and clear the current collision mesh.
Get the corresponding visual data if there is any.
If there is visual data, use
collisionVHACD
with the custom solver options to decompose the triangulation of the visual data into an array of collision meshes.Add each collision mesh from the array of collision meshes to the rigid body.
for bodyIdxToReplace = 9:17 % 1. Get current body and clear collision mesh currBody = robot.Bodies{bodyIdxToReplace}; clearCollision(currBody); % 2. Get Corresponding visual data vizData = getVisual(robot.Bodies{bodyIdxToReplace}); % 3. If visual data, decompose visual data if ~isempty(vizData) collisionArray = collisionVHACD(vizData(1).Triangulation,opts); % 4. Add each collision mesh to the rigid body for j = 1:numel(collisionArray) addCollision(currBody,collisionArray{j}); end end end
Show the original collision meshes of the robot arm next to the updated collision mesh of the arm.
tiledlayout(1,2); sgtitle("Rethink Robotics Sawyer") nexttile robotOriginal = loadrobot("rethinkSawyer",DataFormat="row"); show(robotOriginal,Visuals="off",Collisions="on"); title("Before Decomposition") axis auto view(90,90) nexttile show(robot,Visuals="off",Collisions="on"); title("After Decomposition") view(90,90) axis auto
Note that in this case the new collision meshes represent the robot arm more accurately.
Decompose Collision Meshes of Imported Robot
Import KUKA LBR iiwa 14 robot.
robot = importrobot("iiwa14.urdf");
Display the robot with the default collision meshes.
t = tiledlayout(1,2); title(t,"KUKA iiwa 14") nexttile; show(robot,Visuals="off",Collisions="on"); title("Default Collision Meshes"); axis auto nexttile; show(robot); title("Visual Meshes"); axis auto
Import a robot but decompose the collision meshes using voxelized hierarchical approximate convex decomposition (V-HACD).
robotCollisionDecomp = importrobot("iiwa14.urdf",CollisionDecomposition=true);
Display the robot with the updated collision meshes from decomposition.
figure show(robotCollisionDecomp,Visuals="off",Collisions="on"); title("Decomposition of Collision Meshes"); axis auto
By default the V-HACD solver decomposes the collision meshes of the robot. To decompose the visual meshes of the robot, import the robot with custom V-HACD solver options.
options = vhacdOptions("RigidBodyTree",SourceMesh="VisualGeometry"); robotVisualDecomp = importrobot("iiwa14.urdf",CollisionDecomposition=options);
Display the robot with the updated collision meshes from decomposition.
figure show(robotVisualDecomp,Visuals="off",Collisions="on"); title("Decomposition of Visual Meshes"); axis auto
Decompose Nonconvex STL Mesh into Convex Composites
Read an STL file of a ground vehicle to get a triangulation. Then use trisurf
to visualize the mesh.
meshData = stlread("groundvehicle.stl"); trisurf(meshData) view(135,8) axis equal
Use the collisionVHACD
function to decompose the mesh data into an array of collisionMesh
objects.
collisionArray = collisionVHACD(meshData);
Display the collision mesh array.
figure showCollisionArray(collisionArray); title(["Decomposed Ground Vehicle Mesh","Default Solver Options"])
Create solver options that specify a lower maximum number of convex hulls, and decompose the mesh again with the new options.
opts = vhacdOptions("IndividualMesh",SourceMesh="VisualGeometry",MaxNumConvexHulls=5); collisionArray2 = collisionVHACD(meshData,opts);
Display the collision mesh array.
figure showCollisionArray(collisionArray2); title(["Decomposed Ground Vehicle Mesh","Fewer Convex Hulls"])
References
[1] Mammou, Khaled, et al. “Voxelized Hierarchical Approximate Convex Decomposition - V-HACD Version 4.” GitHub, October 24, 2022. https://github.com/kmammou/v-hacd.
Version History
Introduced in R2023b
See Also
MATLAB Command
You clicked a link that corresponds to this MATLAB command:
Run the command by entering it in the MATLAB Command Window. Web browsers do not support MATLAB commands.
Select a Web Site
Choose a web site to get translated content where available and see local events and offers. Based on your location, we recommend that you select: .
You can also select a web site from the following list
How to Get Best Site Performance
Select the China site (in Chinese or English) for best site performance. Other MathWorks country sites are not optimized for visits from your location.
Americas
- América Latina (Español)
- Canada (English)
- United States (English)
Europe
- Belgium (English)
- Denmark (English)
- Deutschland (Deutsch)
- España (Español)
- Finland (English)
- France (Français)
- Ireland (English)
- Italia (Italiano)
- Luxembourg (English)
- Netherlands (English)
- Norway (English)
- Österreich (Deutsch)
- Portugal (English)
- Sweden (English)
- Switzerland
- United Kingdom (English)
Asia Pacific
- Australia (English)
- India (English)
- New Zealand (English)
- 中国
- 日本Japanese (日本語)
- 한국Korean (한국어)