curobo.geom.sdf.world_blox module
- class WorldBloxCollision(
- config: WorldCollisionConfig,
Bases:
WorldVoxelCollision
World Collision Representaiton using Nvidia’s nvblox library.
This class depends on pytorch wrapper for nvblox. Additionally, this representation does not support batched environments as we only store one world via nvblox.
There are two ways to use nvblox, one is by loading maps from disk and the other is by creating maps online. In both these instances, we might load more than one map and need to check collisions against all maps.
To facilitate online map creation and updation, we build apis in this class that provide.
- load_collision_model(
- world_model: WorldConfig,
- fix_cache_reference: bool = False,
- clear_cache()
- _get_blox_sdf(
- query_spheres,
- collision_query_buffer: CollisionQueryBuffer,
- weight,
- activation_distance,
- return_loss: bool = False,
- compute_esdf: bool = False,
- _get_blox_swept_sdf(
- query_spheres,
- collision_query_buffer,
- weight,
- activation_distance,
- speed_dt,
- sweep_steps,
- enable_speed_metric,
- return_loss=False,
- get_sphere_distance(
- query_sphere: Tensor,
- collision_query_buffer: CollisionQueryBuffer,
- weight: Tensor,
- activation_distance: Tensor,
- env_query_idx: Tensor | None = None,
- return_loss: bool = False,
- sum_collisions: bool = True,
- compute_esdf: bool = False,
Computes the signed distance via analytic function Args: tensor_sphere: b, n, 4
- get_sphere_collision(
- query_sphere,
- collision_query_buffer: CollisionQueryBuffer,
- weight: Tensor,
- activation_distance: Tensor,
- env_query_idx=None,
- return_loss: bool = False,
- **kwargs,
Computes the signed distance via analytic function Args: tensor_sphere: b, n, 4 we assume we don’t need gradient for this function. If you need gradient, use get_sphere_distance
- get_swept_sphere_distance(
- query_sphere,
- collision_query_buffer: CollisionQueryBuffer,
- weight: Tensor,
- activation_distance: Tensor,
- speed_dt: Tensor,
- sweep_steps: int,
- enable_speed_metric=False,
- env_query_idx: Tensor | None = None,
- return_loss: bool = False,
- sum_collisions: bool = True,
Computes the signed distance via analytic function Args: tensor_sphere: b, n, 4
- get_swept_sphere_collision(
- query_sphere,
- collision_query_buffer: CollisionQueryBuffer,
- weight: Tensor,
- sweep_steps,
- activation_distance: Tensor,
- speed_dt: Tensor,
- enable_speed_metric=False,
- env_query_idx: Tensor | None = None,
- return_loss: bool = False,
Computes the signed distance via analytic function Args: tensor_sphere: b, n, 4
- update_blox_pose( )
- get_bounding_spheres(
- bounding_box: Cuboid,
- obstacle_name: str | None = None,
- 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,
- clear_region: bool = False,
- add_camera_frame(
- camera_observation: CameraObservation,
- layer_name: str,
- update_blox_hashes()
- _create_mesh_cache(
- mesh_cache,
- _create_obb_cache(
- obb_cache,
- _get_sdf(
- query_spheres,
- collision_query_buffer: CollisionQueryBuffer,
- weight: Tensor,
- activation_distance: Tensor,
- env_query_idx=None,
- return_loss=False,
- compute_esdf=False,
- _get_swept_sdf(
- query_spheres,
- collision_query_buffer: CollisionQueryBuffer,
- weight: Tensor,
- activation_distance: Tensor,
- speed_dt: Tensor,
- sweep_steps: int,
- enable_speed_metric=False,
- env_query_idx=None,
- return_loss: bool = False,
- _init_cache()
- _load_collision_model_in_cache(
- world_config: WorldConfig,
- env_idx: int = 0,
- fix_cache_reference: bool = False,
- _load_mesh_into_cache(
- mesh: Mesh,
- _load_voxel_collision_model_in_cache(
- world_config: WorldConfig,
- env_idx: int = 0,
- fix_cache_reference: bool = False,
TODO:
_extended_summary_
- Parameters:
world_config – _description_
env_idx – _description_
fix_cache_reference – _description_
- add_obb_from_raw(
- name: str,
- dims: Tensor,
- env_idx: int,
- w_obj_pose: Pose | None = None,
- obj_w_pose: Pose | None = None,
Args: dims: lenght, width, height position: x,y,z rotation: matrix (3x3)
- checker_type: CollisionCheckerType = 'PRIMITIVE'
- clear_voxelization_cache()
- create_collision_cache(
- mesh_cache=None,
- obb_cache=None,
- n_envs=None,
- enable_mesh( )
Update obstacle dimensions
- Parameters:
obj_dims (torch.Tensor) – [dim.x,dim.y, dim.z], give as [b,3]
obj_idx (torch.Tensor or int) –
- enable_obb( )
Update obstacle dimensions
- Parameters:
obj_dims (torch.Tensor) – [dim.x,dim.y, dim.z], give as [b,3]
obj_idx (torch.Tensor or int) –
- enable_voxel( )
Update obstacle dimensions
- Parameters:
obj_dims (torch.Tensor) – [dim.x,dim.y, dim.z], give as [b,3]
obj_idx (torch.Tensor or int) –
- get_esdf_in_bounding_box(
- cuboid: Cuboid = Cuboid(name='test', pose=[0, 0, 0, 1, 0, 0, 0], scale=None, color=None, texture_id=None, texture=None, material=Material(metallic=0.0, roughness=0.4), tensor_args=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), dims=[1, 1, 1]),
- voxel_size: float = 0.02,
- dtype=torch.float32,
- get_mesh_in_bounding_box(
- cuboid: Cuboid = Cuboid(name='test', pose=[0, 0, 0, 1, 0, 0, 0], scale=None, color=None, texture_id=None, texture=None, material=Material(metallic=0.0, roughness=0.4), tensor_args=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), dims=[1, 1, 1]),
- voxel_size: float = 0.02,
- get_occupancy_in_bounding_box(
- cuboid: Cuboid = Cuboid(name='test', pose=[0, 0, 0, 1, 0, 0, 0], scale=None, color=None, texture_id=None, texture=None, material=Material(metallic=0.0, roughness=0.4), tensor_args=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), dims=[1, 1, 1]),
- voxel_size: float = 0.02,
- get_sphere_trace(
- query_sphere,
- collision_query_buffer: CollisionQueryBuffer,
- weight: Tensor,
- sweep_steps: int,
- env_query_idx: Tensor | None = None,
- return_loss: bool = False,
- get_voxels_in_bounding_box(
- cuboid: Cuboid = Cuboid(name='test', pose=[0, 0, 0, 1, 0, 0, 0], scale=None, color=None, texture_id=None, texture=None, material=Material(metallic=0.0, roughness=0.4), tensor_args=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), dims=[1, 1, 1]),
- voxel_size: float = 0.02,
- load_batch_collision_model(
- world_config_list: List[WorldConfig],
Load voxel grid for batched environments
_extended_summary_
- Parameters:
world_config_list – _description_
- Returns:
_description_
- static load_from_dict(
- world_coll_checker_dict: Dict,
- world_model_dict: WorldConfig | Dict | List[WorldConfig] | 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),
- max_distance: torch.Tensor | float = 0.1
- max_esdf_distance: torch.Tensor | float = 100.0
- update_all_mesh_pose(
- w_obj_pose: Pose | None = None,
- obj_w_pose: Pose | None = None,
- name: List[str] | None = None,
- env_obj_idx: Tensor | None = None,
- env_idx: int = 0,
Update poses for a list of meshes in the same environment
- Parameters:
w_obj_pose (Optional[Pose], optional) – _description_. Defaults to None.
obj_w_pose (Optional[Pose], optional) – _description_. Defaults to None.
name (Optional[List[str]], optional) – _description_. Defaults to None.
env_obj_idx (Optional[torch.Tensor], optional) – _description_. Defaults to None.
env_idx (int, optional) – _description_. Defaults to 0.
- update_mesh_from_warp(
- warp_mesh_idx: int,
- w_obj_pose: Pose | None = None,
- obj_w_pose: Pose | None = None,
- obj_idx: int = 0,
- env_idx: int = 0,
- name: str | None = None,
- update_mesh_pose(
- w_obj_pose: Pose | None = None,
- obj_w_pose: Pose | None = None,
- name: str | None = None,
- env_obj_idx: Tensor | None = None,
- env_idx: int = 0,
- update_mesh_pose_env(
- w_obj_pose: Pose | None = None,
- obj_w_pose: Pose | None = None,
- name: str | None = None,
- env_obj_idx: Tensor | None = None,
- env_idx: List[int] = [0],
Update pose of a single object in a list of environments
- Parameters:
w_obj_pose (Optional[Pose], optional) – _description_. Defaults to None.
obj_w_pose (Optional[Pose], optional) – _description_. Defaults to None.
name (Optional[List[str]], optional) – _description_. Defaults to None.
env_obj_idx (Optional[torch.Tensor], optional) – _description_. Defaults to None.
env_idx (List[int], optional) – _description_. Defaults to [0].
- update_obb_dims( )
Update obstacle dimensions
- Parameters:
obj_dims (torch.Tensor) – [dim.x,dim.y, dim.z], give as [b,3]
obj_idx (torch.Tensor or int) –
- update_obb_pose(
- w_obj_pose: Pose | None = None,
- obj_w_pose: Pose | None = None,
- name: str | None = None,
- env_obj_idx: Tensor | None = None,
- env_idx: int = 0,
Update pose of a specific objects. This also updates the signed distance grid to account for the updated object pose. Args: obj_w_pose: Pose obj_idx:
- update_voxel_features( )
Update pose of a specific objects. This also updates the signed distance grid to account for the updated object pose. Args: obj_w_pose: Pose obj_idx:
- update_voxel_pose(
- w_obj_pose: Pose | None = None,
- obj_w_pose: Pose | None = None,
- name: str | None = None,
- env_obj_idx: Tensor | None = None,
- env_idx: int = 0,
Update pose of a specific objects. This also updates the signed distance grid to account for the updated object pose. Args: obj_w_pose: Pose obj_idx:
- world_model: List[WorldConfig] | WorldConfig | None = None
- tensor_args: TensorDeviceType