curobo.geom.types module¶
Geometry types are defined in this module. See Collision World Representation for more information.
- class Obstacle(
- name: str,
- pose: ~typing.List[float] | None = None,
- scale: ~typing.List[float] | None = None,
- color: ~typing.List[float] | None = None,
- texture_id: str | None = None,
- texture: str | None = None,
- material: ~curobo.geom.types.Material = <factory>,
- tensor_args: ~curobo.types.base.TensorDeviceType = <factory>,
Bases:
object
Base class for all obstacles.
- scale: List[float] | None = None¶
Scale obsctacle. This is only implemented for
Mesh
andPointCloud
obstacles.
- tensor_args: TensorDeviceType¶
Device and floating point precision to use for tensors.
- get_trimesh_mesh( ) Trimesh ¶
Create a trimesh instance from the obstacle representation.
- Parameters:
process (bool, optional) – process when loading from file. Defaults to True.
- Raises:
NotImplementedError – requires implementation in derived class.
- Returns:
instance of obstacle as a trimesh.
- Return type:
- save_as_mesh( )¶
Save obstacle as a mesh file.
- Parameters:
file_path – Path to save mesh file.
transform_with_pose – Transform obstacle with pose before saving.
- get_cuboid() Cuboid ¶
Get oriented bounding box of obstacle (OBB).
- Returns:
returns obstacle as a cuboid.
- Return type:
- get_transform_matrix() ndarray ¶
Get homogenous transformation matrix from pose.
- Returns:
transformation matrix.
- Return type:
np.ndarray
- get_sphere(
- n: int = 1,
Compute a sphere that fits in the volume of the object.
- Parameters:
n – number of spheres
- Returns:
spheres
- get_bounding_spheres(
- n_spheres: int = 1,
- surface_sphere_radius: float = 0.002,
- fit_type: SphereFitType = SphereFitType.VOXEL_VOLUME_SAMPLE_SURFACE,
- voxelize_method: str = 'ray',
- pre_transform_pose: Pose | None = None,
- tensor_args: TensorDeviceType = TensorDeviceType(device=device(type='cuda', index=0), dtype=torch.float32, collision_geometry_dtype=torch.float32, collision_gradient_dtype=torch.float32, collision_distance_dtype=torch.float32),
Compute n spheres that fits in the volume of the object.
- Parameters:
n – number of spheres
- Returns:
spheres
- class Cuboid(
- name: str,
- pose: ~typing.List[float] | None = None,
- scale: ~typing.List[float] | None = None,
- color: ~typing.List[float] | None = None,
- texture_id: str | None = None,
- texture: str | None = None,
- material: ~curobo.geom.types.Material = <factory>,
- tensor_args: ~curobo.types.base.TensorDeviceType = <factory>,
- dims: ~typing.List[float] = <factory>,
Bases:
Obstacle
Represent obstacle as a cuboid.
- get_trimesh_mesh( ) Trimesh ¶
Create a trimesh instance from the obstacle representation. :param process: Flag is not used. :param process_color: Flag is not used.
- Returns:
Instance of obstacle as a trimesh.
- Return type:
- get_bounding_spheres(
- n_spheres: int = 1,
- surface_sphere_radius: float = 0.002,
- fit_type: SphereFitType = SphereFitType.VOXEL_VOLUME_SAMPLE_SURFACE,
- voxelize_method: str = 'ray',
- pre_transform_pose: Pose | None = None,
- tensor_args: TensorDeviceType = TensorDeviceType(device=device(type='cuda', index=0), dtype=torch.float32, collision_geometry_dtype=torch.float32, collision_gradient_dtype=torch.float32, collision_distance_dtype=torch.float32),
Compute n spheres that fits in the volume of the object.
- Parameters:
n – number of spheres
- Returns:
spheres
- get_cuboid() Cuboid ¶
Get oriented bounding box of obstacle (OBB).
- Returns:
returns obstacle as a cuboid.
- Return type:
- get_sphere(
- n: int = 1,
Compute a sphere that fits in the volume of the object.
- Parameters:
n – number of spheres
- Returns:
spheres
- get_transform_matrix() ndarray ¶
Get homogenous transformation matrix from pose.
- Returns:
transformation matrix.
- Return type:
np.ndarray
- save_as_mesh( )¶
Save obstacle as a mesh file.
- Parameters:
file_path – Path to save mesh file.
transform_with_pose – Transform obstacle with pose before saving.
- scale: List[float] | None = None¶
Scale obsctacle. This is only implemented for
Mesh
andPointCloud
obstacles.
- tensor_args: TensorDeviceType¶
Device and floating point precision to use for tensors.
- class Capsule(
- name: str,
- pose: ~typing.List[float] | None = None,
- scale: ~typing.List[float] | None = None,
- color: ~typing.List[float] | None = None,
- texture_id: str | None = None,
- texture: str | None = None,
- material: ~curobo.geom.types.Material = <factory>,
- tensor_args: ~curobo.types.base.TensorDeviceType = <factory>,
- radius: float = 0.0,
- base: ~typing.List[float] = <factory>,
- tip: ~typing.List[float] = <factory>,
Bases:
Obstacle
Represent obstacle as a capsule.
- get_trimesh_mesh( ) Trimesh ¶
Create a trimesh instance from the obstacle representation.
- Parameters:
process – Flag is not used.
process_color – Flag is not used.
- Returns:
Instance of obstacle as a trimesh.
- Return type:
- get_bounding_spheres(
- n_spheres: int = 1,
- surface_sphere_radius: float = 0.002,
- fit_type: SphereFitType = SphereFitType.VOXEL_VOLUME_SAMPLE_SURFACE,
- voxelize_method: str = 'ray',
- pre_transform_pose: Pose | None = None,
- tensor_args: TensorDeviceType = TensorDeviceType(device=device(type='cuda', index=0), dtype=torch.float32, collision_geometry_dtype=torch.float32, collision_gradient_dtype=torch.float32, collision_distance_dtype=torch.float32),
Compute n spheres that fits in the volume of the object.
- Parameters:
n – number of spheres
- Returns:
spheres
- get_cuboid() Cuboid ¶
Get oriented bounding box of obstacle (OBB).
- Returns:
returns obstacle as a cuboid.
- Return type:
- get_sphere(
- n: int = 1,
Compute a sphere that fits in the volume of the object.
- Parameters:
n – number of spheres
- Returns:
spheres
- get_transform_matrix() ndarray ¶
Get homogenous transformation matrix from pose.
- Returns:
transformation matrix.
- Return type:
np.ndarray
- save_as_mesh( )¶
Save obstacle as a mesh file.
- Parameters:
file_path – Path to save mesh file.
transform_with_pose – Transform obstacle with pose before saving.
- scale: List[float] | None = None¶
Scale obsctacle. This is only implemented for
Mesh
andPointCloud
obstacles.
- tensor_args: TensorDeviceType¶
Device and floating point precision to use for tensors.
- class Cylinder(
- name: str,
- pose: ~typing.List[float] | None = None,
- scale: ~typing.List[float] | None = None,
- color: ~typing.List[float] | None = None,
- texture_id: str | None = None,
- texture: str | None = None,
- material: ~curobo.geom.types.Material = <factory>,
- tensor_args: ~curobo.types.base.TensorDeviceType = <factory>,
- radius: float = 0.0,
- height: float = 0.0,
Bases:
Obstacle
Obstacle represented as a cylinder.
- get_trimesh_mesh( ) Trimesh ¶
Create a trimesh instance from the obstacle representation.
- Parameters:
process – Flag is not used.
process_color – Flag is not used.
- Returns:
Instance of obstacle as a trimesh.
- Return type:
- get_bounding_spheres(
- n_spheres: int = 1,
- surface_sphere_radius: float = 0.002,
- fit_type: SphereFitType = SphereFitType.VOXEL_VOLUME_SAMPLE_SURFACE,
- voxelize_method: str = 'ray',
- pre_transform_pose: Pose | None = None,
- tensor_args: TensorDeviceType = TensorDeviceType(device=device(type='cuda', index=0), dtype=torch.float32, collision_geometry_dtype=torch.float32, collision_gradient_dtype=torch.float32, collision_distance_dtype=torch.float32),
Compute n spheres that fits in the volume of the object.
- Parameters:
n – number of spheres
- Returns:
spheres
- get_cuboid() Cuboid ¶
Get oriented bounding box of obstacle (OBB).
- Returns:
returns obstacle as a cuboid.
- Return type:
- get_sphere(
- n: int = 1,
Compute a sphere that fits in the volume of the object.
- Parameters:
n – number of spheres
- Returns:
spheres
- get_transform_matrix() ndarray ¶
Get homogenous transformation matrix from pose.
- Returns:
transformation matrix.
- Return type:
np.ndarray
- save_as_mesh( )¶
Save obstacle as a mesh file.
- Parameters:
file_path – Path to save mesh file.
transform_with_pose – Transform obstacle with pose before saving.
- scale: List[float] | None = None¶
Scale obsctacle. This is only implemented for
Mesh
andPointCloud
obstacles.
- tensor_args: TensorDeviceType¶
Device and floating point precision to use for tensors.
- class Sphere(
- name: str,
- pose: ~typing.List[float] | None = None,
- scale: ~typing.List[float] | None = None,
- color: ~typing.List[float] | None = None,
- texture_id: str | None = None,
- texture: str | None = None,
- material: ~curobo.geom.types.Material = <factory>,
- tensor_args: ~curobo.types.base.TensorDeviceType = <factory>,
- radius: float = 0.0,
- position: ~typing.List[float] | None = None,
Bases:
Obstacle
Obstacle represented as a sphere.
- get_trimesh_mesh( ) Trimesh ¶
Create a trimesh instance from the obstacle representation.
- Parameters:
process – Flag is not used.
process_color – Flag is not used.
- Returns:
Instance of obstacle as a trimesh.
- Return type:
- get_cuboid() Cuboid ¶
Get oriented bounding box of obstacle (OBB).
- Returns:
returns obstacle as a cuboid.
- Return type:
- get_bounding_spheres(
- n_spheres: int = 1,
- surface_sphere_radius: float = 0.002,
- fit_type: SphereFitType = SphereFitType.VOXEL_VOLUME_SAMPLE_SURFACE,
- voxelize_method: str = 'ray',
- pre_transform_pose: Pose | None = None,
- tensor_args: TensorDeviceType = TensorDeviceType(device=device(type='cuda', index=0), dtype=torch.float32, collision_geometry_dtype=torch.float32, collision_gradient_dtype=torch.float32, collision_distance_dtype=torch.float32),
Compute n spheres that fits in the volume of the object.
- Parameters:
n – number of spheres
- Returns:
spheres
- get_sphere(
- n: int = 1,
Compute a sphere that fits in the volume of the object.
- Parameters:
n – number of spheres
- Returns:
spheres
- get_transform_matrix() ndarray ¶
Get homogenous transformation matrix from pose.
- Returns:
transformation matrix.
- Return type:
np.ndarray
- save_as_mesh( )¶
Save obstacle as a mesh file.
- Parameters:
file_path – Path to save mesh file.
transform_with_pose – Transform obstacle with pose before saving.
- scale: List[float] | None = None¶
Scale obsctacle. This is only implemented for
Mesh
andPointCloud
obstacles.
- tensor_args: TensorDeviceType¶
Device and floating point precision to use for tensors.
- class Mesh(
- name: str,
- pose: ~typing.List[float] | None = None,
- scale: ~typing.List[float] | None = None,
- color: ~typing.List[float] | None = None,
- texture_id: str | None = None,
- texture: str | None = None,
- material: ~curobo.geom.types.Material = <factory>,
- tensor_args: ~curobo.types.base.TensorDeviceType = <factory>,
- file_path: str | None = None,
- file_string: str | None = None,
- urdf_path: str | None = None,
- vertices: ~typing.List[~typing.List[float]] | None = None,
- faces: ~typing.List[int] | None = None,
- vertex_colors: ~typing.List[~typing.List[float]] | None = None,
- vertex_normals: ~typing.List[~typing.List[float]] | None = None,
- face_colors: ~typing.List[~typing.List[float]] | None = None,
Bases:
Obstacle
Obstacle represented as mesh.
- get_trimesh_mesh( ) Trimesh ¶
Create a trimesh instance from the obstacle representation.
- Parameters:
process – process flag passed to
trimesh.load
.process_color – if True, load mesh visual from texture.
- Returns:
Instance of obstacle as a trimesh.
- Return type:
- update_material()¶
Load material into vertex_colors and face_colors.
- get_mesh_data(
- process: bool = True,
Get vertices and faces of mesh.
- static from_pointcloud(
- pointcloud: ndarray,
- pitch: float = 0.02,
- name='world_pc',
- pose: List[float] = [0, 0, 0, 1, 0, 0, 0],
- filter_close_points: float = 0.0,
Create a mesh from a pointcloud using marching cubes.
- Parameters:
pointcloud – Input pointcloud of shape [n_pts, 3].
pitch – Pitch of marching cubes.
name – Name to asiign to created mesh.
pose – Pose to assign to created mesh.
filter_close_points – filter points that are closer than this threshold. Threshold is in meters and should be positive.
- Returns:
Mesh created from pointcloud.
- Return type:
- get_bounding_spheres(
- n_spheres: int = 1,
- surface_sphere_radius: float = 0.002,
- fit_type: SphereFitType = SphereFitType.VOXEL_VOLUME_SAMPLE_SURFACE,
- voxelize_method: str = 'ray',
- pre_transform_pose: Pose | None = None,
- tensor_args: TensorDeviceType = TensorDeviceType(device=device(type='cuda', index=0), dtype=torch.float32, collision_geometry_dtype=torch.float32, collision_gradient_dtype=torch.float32, collision_distance_dtype=torch.float32),
Compute n spheres that fits in the volume of the object.
- Parameters:
n – number of spheres
- Returns:
spheres
- get_cuboid() Cuboid ¶
Get oriented bounding box of obstacle (OBB).
- Returns:
returns obstacle as a cuboid.
- Return type:
- get_sphere(
- n: int = 1,
Compute a sphere that fits in the volume of the object.
- Parameters:
n – number of spheres
- Returns:
spheres
- get_transform_matrix() ndarray ¶
Get homogenous transformation matrix from pose.
- Returns:
transformation matrix.
- Return type:
np.ndarray
- save_as_mesh( )¶
Save obstacle as a mesh file.
- Parameters:
file_path – Path to save mesh file.
transform_with_pose – Transform obstacle with pose before saving.
- scale: List[float] | None = None¶
Scale obsctacle. This is only implemented for
Mesh
andPointCloud
obstacles.
- tensor_args: TensorDeviceType¶
Device and floating point precision to use for tensors.
- class BloxMap(
- name: str,
- pose: ~typing.List[float] | None = None,
- scale: ~typing.List[float] = <factory>,
- color: ~typing.List[float] | None = None,
- texture_id: str | None = None,
- texture: str | None = None,
- material: ~curobo.geom.types.Material = <factory>,
- tensor_args: ~curobo.types.base.TensorDeviceType = <factory>,
- map_path: str | None = None,
- voxel_size: float = 0.02,
- integrator_type: str = 'tsdf',
- mesh_file_path: str | None = None,
- mapper_instance: ~typing.Any | None = None,
- mesh: ~curobo.geom.types.Mesh | None = None,
Bases:
Obstacle
Obstacle represented as a nvblox ESDF layer.
- integrator_type: str = 'tsdf'¶
[“tsdf”, “occupancy”]
- Type:
Integrator type to use in nvblox. Options
- mapper_instance: Any = None¶
Instance of nvblox mapper. Useful for passing a pre-initialized mapper.
- mesh: Mesh | None = None¶
Mesh representation of the map. Useful for rendering. Not used in collision checking.
- get_trimesh_mesh( ) Trimesh | None ¶
Get trimesh mesh representation of the map. Only available if mesh_file_path is set.
- Parameters:
process – Process flag passed to
trimesh.load
.process_color – Load mesh visual from texture.
- Returns:
Trimesh mesh representation of the map.
- Return type:
Union[trimesh.Trimesh, None]
- get_bounding_spheres(
- n_spheres: int = 1,
- surface_sphere_radius: float = 0.002,
- fit_type: SphereFitType = SphereFitType.VOXEL_VOLUME_SAMPLE_SURFACE,
- voxelize_method: str = 'ray',
- pre_transform_pose: Pose | None = None,
- tensor_args: TensorDeviceType = TensorDeviceType(device=device(type='cuda', index=0), dtype=torch.float32, collision_geometry_dtype=torch.float32, collision_gradient_dtype=torch.float32, collision_distance_dtype=torch.float32),
Compute n spheres that fits in the volume of the object.
- Parameters:
n – number of spheres
- Returns:
spheres
- get_cuboid() Cuboid ¶
Get oriented bounding box of obstacle (OBB).
- Returns:
returns obstacle as a cuboid.
- Return type:
- get_sphere(
- n: int = 1,
Compute a sphere that fits in the volume of the object.
- Parameters:
n – number of spheres
- Returns:
spheres
- get_transform_matrix() ndarray ¶
Get homogenous transformation matrix from pose.
- Returns:
transformation matrix.
- Return type:
np.ndarray
- save_as_mesh( )¶
Save obstacle as a mesh file.
- Parameters:
file_path – Path to save mesh file.
transform_with_pose – Transform obstacle with pose before saving.
- tensor_args: TensorDeviceType¶
Device and floating point precision to use for tensors.
- class PointCloud(
- name: str,
- pose: ~typing.List[float] | None = None,
- scale: ~typing.List[float] | None = None,
- color: ~typing.List[float] | None = None,
- texture_id: str | None = None,
- texture: str | None = None,
- material: ~curobo.geom.types.Material = <factory>,
- tensor_args: ~curobo.types.base.TensorDeviceType = <factory>,
- points: ~torch.Tensor | ~numpy.ndarray | ~typing.List[~typing.List[float]] | None = None,
- points_features: ~torch.Tensor | ~numpy.ndarray | ~typing.List[~typing.List[float]] | None = None,
Bases:
Obstacle
Obstacle represented as a pointcloud.
- get_trimesh_mesh( ) Trimesh ¶
Create a trimesh instance from the obstacle representation.
- Parameters:
process – Not used.
process_color – Not used.
- Returns:
Instance of obstacle as a trimesh.
- Return type:
- get_mesh_data(
- process: bool = True,
Get mesh data from pointcloud.
- Parameters:
process – process flag passed to
trimesh.load
.- Returns:
vertices and faces of mesh.
- Return type:
verts, faces
- static from_camera_observation(
- camera_obs: CameraObservation,
- name: str = 'pc_obstacle',
- pose: List[float] | None = None,
Create a pointcloud from a camera observation.
- Parameters:
camera_obs – Input camera observation.
name – Name to assign to created pointcloud.
pose – Pose to assign to created pointcloud.
- Returns:
Pointcloud created from camera observation.
- Return type:
- get_bounding_spheres(
- n_spheres: int = 1,
- surface_sphere_radius: float = 0.002,
- fit_type: SphereFitType = SphereFitType.VOXEL_VOLUME_SAMPLE_SURFACE,
- voxelize_method: str = 'ray',
- pre_transform_pose: Pose | None = None,
- tensor_args: TensorDeviceType = TensorDeviceType(device=device(type='cuda', index=0), dtype=torch.float32, collision_geometry_dtype=torch.float32, collision_gradient_dtype=torch.float32, collision_distance_dtype=torch.float32),
Compute n spheres that fits in the volume of the object.
- Parameters:
n – number of spheres
- Returns:
spheres
- get_cuboid() Cuboid ¶
Get oriented bounding box of obstacle (OBB).
- Returns:
returns obstacle as a cuboid.
- Return type:
- get_sphere(
- n: int = 1,
Compute a sphere that fits in the volume of the object.
- Parameters:
n – number of spheres
- Returns:
spheres
- get_transform_matrix() ndarray ¶
Get homogenous transformation matrix from pose.
- Returns:
transformation matrix.
- Return type:
np.ndarray
- save_as_mesh( )¶
Save obstacle as a mesh file.
- Parameters:
file_path – Path to save mesh file.
transform_with_pose – Transform obstacle with pose before saving.
- scale: List[float] | None = None¶
Scale obsctacle. This is only implemented for
Mesh
andPointCloud
obstacles.
- tensor_args: TensorDeviceType¶
Device and floating point precision to use for tensors.
- class VoxelGrid(
- name: str,
- pose: ~typing.List[float] | None = None,
- scale: ~typing.List[float] | None = None,
- color: ~typing.List[float] | None = None,
- texture_id: str | None = None,
- texture: str | None = None,
- material: ~curobo.geom.types.Material = <factory>,
- tensor_args: ~curobo.types.base.TensorDeviceType = <factory>,
- dims: ~typing.List[float] = <factory>,
- voxel_size: float = 0.02,
- feature_tensor: ~torch.Tensor | None = None,
- xyzr_tensor: ~torch.Tensor | None = None,
- feature_dtype: ~torch.dtype = torch.float32,
Bases:
Obstacle
VoxelGrid representation of an obstacle. Requires voxel to contain ESDF.
- create_xyzr_tensor(
- transform_to_origin: bool = False,
- tensor_args: TensorDeviceType = TensorDeviceType(device=device(type='cuda', index=0), dtype=torch.float32, collision_geometry_dtype=torch.float32, collision_gradient_dtype=torch.float32, collision_distance_dtype=torch.float32),
Create XYZR tensor of voxel grid.
- Parameters:
transform_to_origin – Transform points to origin.
tensor_args – Device and floating point precision to use for tensors.
- Returns:
XYZR tensor of voxel grid with r referring to voxel size.
- Return type:
xyzr_tensor
- get_occupied_voxels( ) Tensor ¶
Get occupied voxels from voxel grid.
- Parameters:
feature_threshold – esdf value threshold to consider as occupied.
- Returns:
occupied voxels as a tensor of shape [occupied_voxels].
- get_bounding_spheres(
- n_spheres: int = 1,
- surface_sphere_radius: float = 0.002,
- fit_type: SphereFitType = SphereFitType.VOXEL_VOLUME_SAMPLE_SURFACE,
- voxelize_method: str = 'ray',
- pre_transform_pose: Pose | None = None,
- tensor_args: TensorDeviceType = TensorDeviceType(device=device(type='cuda', index=0), dtype=torch.float32, collision_geometry_dtype=torch.float32, collision_gradient_dtype=torch.float32, collision_distance_dtype=torch.float32),
Compute n spheres that fits in the volume of the object.
- Parameters:
n – number of spheres
- Returns:
spheres
- get_cuboid() Cuboid ¶
Get oriented bounding box of obstacle (OBB).
- Returns:
returns obstacle as a cuboid.
- Return type:
- get_sphere(
- n: int = 1,
Compute a sphere that fits in the volume of the object.
- Parameters:
n – number of spheres
- Returns:
spheres
- get_transform_matrix() ndarray ¶
Get homogenous transformation matrix from pose.
- Returns:
transformation matrix.
- Return type:
np.ndarray
- get_trimesh_mesh( ) Trimesh ¶
Create a trimesh instance from the obstacle representation.
- Parameters:
process (bool, optional) – process when loading from file. Defaults to True.
- Raises:
NotImplementedError – requires implementation in derived class.
- Returns:
instance of obstacle as a trimesh.
- Return type:
- save_as_mesh( )¶
Save obstacle as a mesh file.
- Parameters:
file_path – Path to save mesh file.
transform_with_pose – Transform obstacle with pose before saving.
- scale: List[float] | None = None¶
Scale obsctacle. This is only implemented for
Mesh
andPointCloud
obstacles.
- tensor_args: TensorDeviceType¶
Device and floating point precision to use for tensors.
- class WorldConfig(
- sphere: List[Sphere] | None = None,
- cuboid: List[Cuboid] | None = None,
- capsule: List[Capsule] | None = None,
- cylinder: List[Cylinder] | None = None,
- mesh: List[Mesh] | None = None,
- blox: List[BloxMap] | None = None,
- voxel: List[VoxelGrid] | None = None,
- objects: List[Obstacle] | None = None,
Bases:
Sequence
Representation of World for use in CuRobo.
- clone() WorldConfig ¶
Clone world configuration.
- static from_dict( ) WorldConfig ¶
Load world configuration from dictionary.
- Parameters:
data_dict – World configuration dictionary.
- Returns:
Instance of WorldConfig.
- static create_obb_world(
- current_world: WorldConfig,
Approximate all obstcales to oriented bounding boxes.
- static create_mesh_world(
- current_world: WorldConfig,
- process: bool = False,
Convert all obstacles to meshes. Does not convert
VoxelGrid
,BloxMap
.- Parameters:
current_world – Current world configuration.
process – process flag passed to
trimesh.load
.
- Returns:
World configuration with all obstacles converted to meshes.
- Return type:
- static create_collision_support_world(
- current_world: WorldConfig,
- process: bool = True,
Converts all obstacles to only supported collision types.
- Parameters:
current_world – Current world configuration.
process – process flag passed to
trimesh.load
.
- Returns:
- World configuration with all obstacles converted to supported collision
types.
- Return type:
- static get_scene_graph(
- current_world: WorldConfig,
- process_color: bool = True,
Get trimesh scene graph of world.
- Parameters:
current_world – Current world configuration.
process_color – Load color of meshes.
- Returns:
Scene graph of world.
- Return type:
- static create_merged_mesh_world(
- current_world: WorldConfig,
- process: bool = True,
- process_color: bool = True,
Merge all obstacles in the world to a single mesh.
- Parameters:
current_world – Current world configuration.
process – process flag passed to
trimesh.load
.process_color – Load color of meshes.
- Returns:
World configuration with a single merged mesh as obstacle.
- Return type:
- get_obb_world() WorldConfig ¶
Get world with all obstacles as oriented bounding boxes.
- get_mesh_world( ) WorldConfig ¶
Get world with all obstacles as meshes.
- get_collision_check_world(
- mesh_process: bool = False,
Get world with all obstacles converted to supported collision types.
- save_world_as_mesh( )¶
Save world as a mesh file.
- Parameters:
file_path – Path to save mesh file.
save_as_scene_graph – Save as scene graph.
process_color – Load color of meshes.
- add_obstacle(
- obstacle: Obstacle,
Add obstacle to world.
- Parameters:
obstacle – Obstacle to add to world.
- randomize_color(
- r=[0, 1],
- g=[0, 1],
- b=[0, 1],
Randomize color of objects within the given range
- Parameters:
r – range of red color.
g – range of green color.
b – range of blue color.
- add_color(
- rgba=[0.0, 0.0, 0.0, 1.0],
Update color of obstacles.
- Parameters:
rgba – red, green, blue, alpha values.
- add_material(
- material=Material(metallic=0.0, roughness=0.4),
Add material to all obstacles.
- Parameters:
material – material to add to obstacles.
- get_obstacle(
- name: str,
Get obstacle by name.
- Parameters:
name – Name of obstacle.
- Returns:
Obstacle with given name. If not found, returns None.
- remove_absolute_paths()¶
Remove absolute paths from file paths in obstacles. May not work on Windows.
- _abc_impl = <_abc._abc_data object>¶
- _is_protocol = False¶
- count(
- value,
- index(
- value[,
- start[,
- stop,]]
Raises ValueError if the value is not present.
Supporting start and stop arguments is optional, but recommended.
- tensor_sphere(
- pt: List[float] | array | Tensor,
- radius: float,
- tensor: Tensor | None = None,
- tensor_args: TensorDeviceType = TensorDeviceType(device=device(type='cuda', index=0), dtype=torch.float32, collision_geometry_dtype=torch.float32, collision_gradient_dtype=torch.float32, collision_distance_dtype=torch.float32),
Tensor representation of a sphere.
- Parameters:
pt – Input point.
radius – Radius of sphere.
tensor – Tensor to update. If None, creates a new tensor.
tensor_args – Device and floating point precision to use for tensors.
- Returns:
Tensor representation of sphere.
- Return type:
tensor
- tensor_capsule(
- base: List[float] | Tensor | array,
- tip: List[float] | Tensor | array,
- radius: float,
- tensor: Tensor | None = None,
- tensor_args: TensorDeviceType = TensorDeviceType(device=device(type='cuda', index=0), dtype=torch.float32, collision_geometry_dtype=torch.float32, collision_gradient_dtype=torch.float32, collision_distance_dtype=torch.float32),
Tensor representation of a capsule.
- Parameters:
base – Base of capsule.
tip – Tip of capsule.
radius – radius of capsule.
tensor – Tensor to update. If None, creates a new tensor.
tensor_args – Device and floating point precision to use for tensors.
- Returns:
Tensor representation of capsule.
- Return type:
- tensor_cube(
- pose: List[float],
- dims: List[float],
- tensor_args: TensorDeviceType = TensorDeviceType(device=device(type='cuda', index=0), dtype=torch.float32, collision_geometry_dtype=torch.float32, collision_gradient_dtype=torch.float32, collision_distance_dtype=torch.float32),
Tensor representation of a cube.
- Parameters:
pose – x,y,z, qw, qx, qy, qz.
dims – length, width, height in meters. Frame is at the center of the cube.
tensor_args – Device and floating point precision to use for tensors.
- Returns:
- Tensor representation of cube, first tensor is
dimensions and second tensor is inverse of pose.
- Return type:
List[torch.Tensor, torch.Tensor]
- batch_tensor_cube(
- pose: List[List[float]],
- dims: List[List[float]],
- tensor_args: TensorDeviceType = TensorDeviceType(device=device(type='cuda', index=0), dtype=torch.float32, collision_geometry_dtype=torch.float32, collision_gradient_dtype=torch.float32, collision_distance_dtype=torch.float32),
Tensor representation of a batch of cubes :param pose: Poses of the cubes in x,y,z, qw,qx,qy,qz. :param dims: Dimensions of the cubes. Frame is at the center of the cube. :param tensor_args: Device and floating point precision to use for tensors.
- Returns:
- Tensor representation of cubes, first tensor is dimensions and
second tensor is inverse of poses.
- Return type:
List[torch.Tensor]