I can’t get the correct values for the bounding box of an object imported with the urdf importer.
Here is an example code: test_bbox.zip (1.6 KB)
In this code, I tested to compute the bounding box using [Get Mesh Size] (Frequently Used Python Snippets — Omniverse Robotics documentation) as well as using directly the compute_object_AABB function from world.scene and using the function compute_aabb from omni.isaac.core.utils.bounds.
In the three cases, I got the same result for the dimensions of the bounding box: [0.0225 0.0016 0.0016] while it should give as a result [0.15 0.04 0.04]
Does someone have an idea of how to get the correct bounding box values?
Hello, the bounding box computed is also incorrect if I use the cube defined in Isaac Sim with some scaling.
Here is an example in which the dimensions computed are [0.25, 0.25, 0.25] and it should be [0.5, 0.5, 0.5]
from omni.isaac.kit import SimulationApp
kit = SimulationApp({"headless": False})
from omni.kit.commands import execute
from omni.isaac.core import World
from omni.isaac.core.objects.cuboid import DynamicCuboid
import omni.isaac.core.utils.prims as ipr
from pxr import Usd, UsdGeom
import numpy as np
from omni.isaac.core.utils.bounds import compute_aabb, create_bbox_cache
import omni.timeline
if __name__ == "__main__":
physics_dt = 1 / 240
gravity_magnitude = 9.81
world = World(physics_dt=physics_dt, rendering_dt=physics_dt, stage_units_in_meters=1.0)
world.get_physics_context().set_gravity(-gravity_magnitude)
world.scene.add_default_ground_plane()
world.scene.enable_bounding_boxes_computations()
_, import_config = execute("URDFCreateImportConfig")
# Set defaults
import_config.merge_fixed_joints = False
import_config.convex_decomp = False
import_config.fix_base = False
import_config.import_inertia_tensor = False
prim_path = "/World/cube"
name = "cube"
prim = world.scene.add(
DynamicCuboid(
prim_path=prim_path, # The prim path of the cube in the USD stage
name=name, # The unique name used to retrieve the object from the scene later on
position=np.array([0, 0, 1.0]), # Using the current stage units which is in meters by default.
scale=np.array([0.5, 0.5, 0.5]), # most arguments accept mainly numpy arrays.
color=np.array([0, 0, 1.0]), # RGB channels, going from 0-1
))
# TEST with compute_object_AABB from world.scene
[pos_1, pos_2] = world.scene.compute_object_AABB(name)
size = np.array(pos_2) - np.array(pos_1)
print("Prim size obtained with compute_object_AABB: ", size)
# TEST with Compute World Bound
timeline = omni.timeline.get_timeline_interface()
bbox_cache = UsdGeom.BBoxCache(timeline.get_current_time(), includedPurposes=[UsdGeom.Tokens.default_])
bbox_cache.Clear()
prim = ipr.get_prim_at_path(prim_path)
prim_bbox = bbox_cache.ComputeWorldBound(prim)
prim_range = prim_bbox.ComputeAlignedRange()
prim_size = prim_range.GetSize()
print("Prim size obtained with ComputeWorldBound: ", list(prim_size))
# Test with compute_aabb
cache = create_bbox_cache(use_extents_hint=False)
bb = compute_aabb(cache, prim_path, include_children=True)
prim_size = np.array(bb[3:]) - np.array(bb[:3])
print("Prim size obtained with compute_aabb: ", list(prim_size))
kit.close()
can you take a look at this tutorial, it computes aabb’s at different steps:
# Calculate the bounds of the prim to create a scatter plane of its size
bb_cache = create_bbox_cache()
bbox3d_gf = bb_cache.ComputeLocalBound(prim)
prim_tf_gf = omni.usd.get_world_transform_matrix(prim)
# Calculate the bounds of the prim
bbox3d_gf.Transform(prim_tf_gf)
range_size = bbox3d_gf.GetRange().GetSize()
# Helper function to get the combined bounds of the forklift and pallet
bb_cache = create_bbox_cache()
combined_range_arr = compute_combined_aabb(bb_cache, [forklift_prim.GetPrimPath(), pallet_prim.GetPrimPath()])
When computing the bounding boxes with the method you mentioned above in your example code, the bounding boxes for the different objects seem to be good now (even if we rescale them).
There is just a specific case in which there is still a problem. In one of our urdf (Archive.zip (1.2 KB)), we used as a geometry a box and as a collision a mesh and it seems to cause a problem in the computation of the bounding box afterwards. If a mesh is used for the visual in this urdf then, the bounding box computed is good. It seems to be a work around to solve the problem in this case.