Skip to content

Commit eec1f04

Browse files
authored
Merge pull request #197 from compas-dev/cm_scaled
add scaled to CollisionMesh and use in PlanningScene
2 parents 2a121b3 + b8fbfaf commit eec1f04

File tree

1 file changed

+23
-11
lines changed

1 file changed

+23
-11
lines changed

src/compas_fab/robots/planning_scene.py

Lines changed: 23 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -70,6 +70,17 @@ def scale(self, scale_factor):
7070
S = Scale.from_factors([scale_factor] * 3)
7171
self.mesh.transform(S)
7272

73+
def scaled(self, scale_factor):
74+
"""Copies the collision mesh, and scales the copy uniformly.
75+
76+
Parameters
77+
----------
78+
scale_factor : :obj:`float`
79+
Scale factor.
80+
"""
81+
self.mesh = self.mesh.copy()
82+
self.scale(scale_factor)
83+
7384

7485
class AttachedCollisionMesh(object):
7586
"""Represents a collision mesh that is attached to a :class:`Robot`'s :class:`~compas.robots.Link`.
@@ -164,8 +175,8 @@ def add_collision_mesh(self, collision_mesh, scale=False):
164175
collision_mesh : :class:`CollisionMesh`
165176
The collision mesh we want to add.
166177
scale : :obj:`bool`, optional
167-
If ``True``, the mesh will be scaled according to the robot's scale
168-
factor.
178+
If ``True``, the mesh will be copied and scaled according to
179+
the robot's scale factor.
169180
170181
Returns
171182
-------
@@ -184,7 +195,7 @@ def add_collision_mesh(self, collision_mesh, scale=False):
184195

185196
if scale:
186197
scale_factor = 1. / self.robot.scale_factor
187-
collision_mesh.scale(scale_factor)
198+
collision_mesh.scaled(scale_factor)
188199

189200
self.client.add_collision_mesh(collision_mesh)
190201

@@ -225,8 +236,8 @@ def append_collision_mesh(self, collision_mesh, scale=False):
225236
collision_mesh : :class:`CollisionMesh`
226237
The collision mesh we want to append to the :class:`PlanningScene`.
227238
scale : :obj:`bool`, optional
228-
If ``True``, the mesh will be scaled according to the robot's scale
229-
factor.
239+
If ``True``, the mesh will be copied and scaled according to
240+
the robot's scale factor.
230241
231242
Returns
232243
-------
@@ -245,7 +256,7 @@ def append_collision_mesh(self, collision_mesh, scale=False):
245256

246257
if scale:
247258
scale_factor = 1. / self.robot.scale_factor
248-
collision_mesh.scale(scale_factor)
259+
collision_mesh.scaled(scale_factor)
249260

250261
self.robot.client.append_collision_mesh(collision_mesh)
251262

@@ -259,7 +270,8 @@ def add_attached_collision_mesh(self, attached_collision_mesh, scale=False):
259270
attached to a :class:`Robot`'s :class:`~compas.robots.Link`) that
260271
we want to add to the :class:`PlanningScene`.
261272
scale : :obj:`bool`, optional
262-
If ``True``, the mesh will be scaled using the robot's scale factor.
273+
If ``True``, the mesh will be copied and scaled according to
274+
the robot's scale factor.
263275
264276
Returns
265277
-------
@@ -279,7 +291,7 @@ def add_attached_collision_mesh(self, attached_collision_mesh, scale=False):
279291

280292
if scale:
281293
scale_factor = 1. / self.robot.scale_factor
282-
attached_collision_mesh.collision_mesh.scale(scale_factor)
294+
attached_collision_mesh.collision_mesh.scaled(scale_factor)
283295

284296
self.client.add_attached_collision_mesh(attached_collision_mesh)
285297

@@ -313,8 +325,8 @@ def attach_collision_mesh_to_robot_end_effector(self, collision_mesh, scale=Fals
313325
collision_mesh: :class:`CollisionMesh`
314326
The collision mesh to attach to robot's end effector.
315327
scale : :obj:`bool`, optional
316-
If ``True``, the mesh will be scaled using the robot's scale
317-
factor.
328+
If ``True``, the mesh will be copied and scaled according to
329+
the robot's scale factor.
318330
group : :obj:`str`
319331
The planning group with the end effector we want to attach the mesh
320332
to. Defaults to the robot's main planning group.
@@ -348,7 +360,7 @@ def attach_collision_mesh_to_robot_end_effector(self, collision_mesh, scale=Fals
348360

349361
if scale:
350362
scale_factor = 1. / self.robot.scale_factor
351-
collision_mesh.scale(scale_factor)
363+
collision_mesh.scaled(scale_factor)
352364

353365
ee_link_name = self.robot.get_end_effector_link_name(group)
354366
touch_links = [ee_link_name]

0 commit comments

Comments
 (0)