Skip to content

Commit

Permalink
RigidBody constructor to accept lists of meshes for visualization and…
Browse files Browse the repository at this point in the history
… collision checking, no defaults
  • Loading branch information
yck011522 committed Sep 9, 2024
1 parent 37d6d1f commit 07decdb
Show file tree
Hide file tree
Showing 3 changed files with 65 additions and 11 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -13,12 +13,13 @@

# Add some RigidBodies as stationary obstacles
floor_mesh = Mesh.from_stl(compas_fab.get("planning_scene/floor.stl"))
robot_cell.rigid_body_models["floor"] = RigidBody(floor_mesh)
robot_cell.rigid_body_models["floor"] = RigidBody.from_mesh(floor_mesh)
cone = Mesh.from_stl(compas_fab.get("planning_scene/cone.stl"))
robot_cell.rigid_body_models["cone"] = RigidBody(cone)
robot_cell.rigid_body_models["cone"] = RigidBody.from_mesh(cone)

# Add a target marker as a RigidBody with visual mesh but no collision mesh
target_marker = Mesh.from_obj(compas_fab.get("planning_scene/target_marker.obj"))
robot_cell.rigid_body_models["target_marker"] = RigidBody(target_marker)
robot_cell.rigid_body_models["target_marker"] = RigidBody(target_marker, None)

# The planner object is needed to pass the robot cell into the PyBullet client
planner = PyBulletPlanner(client)
Expand Down
57 changes: 55 additions & 2 deletions src/compas_fab/robots/robot_cell.py
Original file line number Diff line number Diff line change
Expand Up @@ -169,8 +169,8 @@ def get_attached_rigid_bodies_as_attached_collision_meshes(self, robot_cell_stat
class RigidBody(Data):
"""Represents a rigid body."""

def __init__(self, visual_meshes=None, collision_meshes=None):
# type: (Optional[List[Mesh] | Mesh], Optional[List[Mesh] | Mesh]) -> None
def __init__(self, visual_meshes, collision_meshes):
# type: (List[Mesh] | Mesh, List[Mesh] | Mesh) -> None
"""Represents a rigid body.
A rigid body can have different visual and collision meshes.
Expand Down Expand Up @@ -227,6 +227,59 @@ def __data__(self):
"collision_meshes": self.collision_meshes,
}

@classmethod
def from_mesh(cls, mesh):
# type: (Mesh) -> RigidBody
"""Creates a RigidBody from a single mesh.
This function is a convenience function for creating a RigidBody from a single mesh.
The mesh will be used for both visualization and collision checking.
Parameters
----------
mesh : :class:`compas.datastructures.Mesh`
The mesh of the rigid body.
Returns
-------
:class:`compas_fab.robots.RigidBody`
The rigid body.
Notes
-----
If the user would like to use different meshes for visualization and collision checking,
consider using the constructor directly: `RigidBody(visual_meshes, collision_meshes)`.
"""
return cls([mesh], [mesh])

@classmethod
def from_meshes(cls, meshes):
# type: (List[Mesh]) -> RigidBody
"""Creates a RigidBody from a list of meshes.
This function is a convenience function for creating a RigidBody from a list of meshes.
The first mesh will be used for visualization and collision checking.
The rest of the meshes will be used for visualization only.
Parameters
----------
meshes : list of :class:`compas.datastructures.Mesh`
The meshes of the rigid body.
Returns
-------
:class:`compas_fab.robots.RigidBody`
The rigid body.
Notes
-----
If the user would like to use different meshes for visualization and collision checking,
consider using the constructor directly: `RigidBody(visual_meshes, collision_meshes)`.
"""
return cls(meshes, meshes)


class RobotCellState(Data):
"""Represents the state of a robot cell.
Expand Down
12 changes: 6 additions & 6 deletions src/compas_fab/robots/robot_library.py
Original file line number Diff line number Diff line change
Expand Up @@ -491,7 +491,7 @@ def ur5_cone_tool(cls, client=None, load_geometry=True):

# Static Floor as Collision Geometry
floor_mesh = Mesh.from_stl(compas_fab.get("planning_scene/floor.stl"))
robot_cell.rigid_body_models["floor"] = RigidBody(floor_mesh, floor_mesh)
robot_cell.rigid_body_models["floor"] = RigidBody.from_mesh(floor_mesh)

# ------------------------------------------------------------------------
# Create RobotCellState
Expand Down Expand Up @@ -564,11 +564,11 @@ def abb_irb4600_40_255_gripper_one_beam(cls, client=None, load_geometry=True):
[0.0, -0.1, -beam_length * 0.5], [0.2, 0.1, -beam_length * 0.5], beam_length
)
beam_mesh = Mesh.from_shape(beam)
robot_cell.rigid_body_models["beam"] = RigidBody(beam_mesh, beam_mesh)
robot_cell.rigid_body_models["beam"] = RigidBody.from_mesh(beam_mesh)

# Static Floor as Collision Geometry
floor_mesh = Mesh.from_stl(compas_fab.get("planning_scene/floor.stl"))
robot_cell.rigid_body_models["floor"] = RigidBody(floor_mesh, floor_mesh)
robot_cell.rigid_body_models["floor"] = RigidBody.from_mesh(floor_mesh)

# ------------------------------------------------------------------------
# Create RobotCellState
Expand Down Expand Up @@ -634,11 +634,11 @@ def ur10e_gripper_one_beam(cls, client=None, load_geometry=True):
[0.0, -0.05, -beam_length * 0.5], [0.1, 0.05, -beam_length * 0.5], beam_length
)
beam_mesh = Mesh.from_shape(beam)
robot_cell.rigid_body_models["beam"] = RigidBody(beam_mesh, beam_mesh)
robot_cell.rigid_body_models["beam"] = RigidBody.from_mesh(beam_mesh)

# Static Floor as Collision Geometry
floor_mesh = Mesh.from_stl(compas_fab.get("planning_scene/floor.stl"))
robot_cell.rigid_body_models["floor"] = RigidBody(floor_mesh, floor_mesh)
robot_cell.rigid_body_models["floor"] = RigidBody.from_mesh(floor_mesh)

# ------------------------------------------------------------------------
# Create RobotCellState
Expand Down Expand Up @@ -704,7 +704,7 @@ def target_marker(cls, size=1.0):
# Scale the target marker to the desired size
mesh.scale(size)

return RigidBody([mesh], [])
return RigidBody(mesh, None)


if __name__ == "__main__":
Expand Down

0 comments on commit 07decdb

Please sign in to comment.