storm_kit.geom.sdf.robot_world module¶
-
class
RobotWorldCollisionCapsule
(robot_collision_params, world_collision_params, robot_batch_size=1, world_batch_size=1, tensor_args={'device': 'cpu', 'dtype': torch.float32})[source]¶ Bases:
storm_kit.geom.sdf.robot_world.RobotWorldCollision
Collision checking between capsule robot and sphere world
-
class
RobotWorldCollisionPrimitive
(robot_collision_params, world_collision_params, robot_batch_size=1, world_batch_size=1, tensor_args={'device': 'cpu', 'dtype': torch.float32}, bounds=None, grid_resolution=None)[source]¶
-
class
RobotWorldCollisionVoxel
(robot_collision_params, batch_size, label_map, bounds=None, grid_resolution=0.02, tensor_args={'device': device(type='cpu'), 'dtype': torch.float32})[source]¶ Bases:
object
This class can check collision between robot and sdf grid of camera pointcloud.
-
check_robot_mesh_collisions
(link_trans, link_rot, threshold=0.45, return_point_values=False)[source]¶ Checks collision between robot represented by sampling points on mesh surface and pointcloud sdf.
- Parameters
link_trans ([type]) – [description]
link_rot ([type]) – [description]
threshold (float, optional) – [description]. Defaults to 0.45.
return_point_values (bool, optional) – [description]. Defaults to False.
- Returns
[description]
- Return type
[type]
-
check_robot_sphere_collisions
(link_trans, link_rot)[source]¶ Checks collision between robot spheres and pointcloud sdf grid
- Parameters
link_trans ([type]) – [description]
link_rot ([type]) – [description]
- Returns
[description]
- Return type
[type]
-