CollisionMesh
- class compas_fab.robots.CollisionMesh(mesh, id, frame=None, root_name=None)[source]
Bases:
object
Represents a collision mesh.
- Parameters
mesh (
compas.datastructures.Mesh
) – The collision mesh. Ideally it is as coarse as possible.id (
str
) – The id of the mesh, used to identify it for later operations (add_collision_mesh()
,remove_collision_mesh()
,append_collision_mesh()
etc.)frame (
compas.geometry.Frame
, optional) – The frame of the mesh. Defaults to :meth:`~compas.geometry.Frame.worldXY().root_name (
str
) – The name of the root link the collision mesh will be placed in. Defaults to ‘world’.
- Attributes
mesh (
compas.datastructures.Mesh
) – The collision mesh. Ideally it is as coarse as possible.id (
str
) – The id of the mesh, used to identify it for later operations (add_collision_mesh()
,remove_collision_mesh()
,append_collision_mesh()
etc.)frame (
compas.geometry.Frame
, optional) – The frame of the mesh. Defaults to :meth:`~compas.geometry.Frame.worldXY().root_name (
str
) – The name of the root link the collision mesh will be placed in. Defaults to ‘world’.
Examples
>>> mesh = Mesh.from_stl(compas_fab.get('planning_scene/floor.stl')) >>> cm = CollisionMesh(mesh, 'floor') >>> cm.frame Frame(Point(0.000, 0.000, 0.000), Vector(1.000, 0.000, 0.000), Vector(0.000, 1.000, 0.000))
Methods
__init__
(mesh, id[, frame, root_name])Initialize self.
from_data
(data)Construct a collision mesh from its data representation.
scale
(scale_factor)Scales the collision mesh uniformly.
scaled
(scale_factor)Copies the collision mesh, and scales the copy uniformly.
to_data
()Get the data dictionary that represents the collision mesh.
Attributes
data
The data representing the collision mesh.