|
2 | 2 | from __future__ import division |
3 | 3 | from __future__ import print_function |
4 | 4 |
|
5 | | -from compas.datastructures import mesh_transform |
6 | 5 | from compas.geometry import Frame |
7 | 6 | from compas.geometry import Scale |
8 | 7 |
|
@@ -43,14 +42,16 @@ def __init__(self, mesh, id, frame=None, root_name=None): |
43 | 42 | self.frame = frame or Frame.worldXY() |
44 | 43 | self.root_name = root_name or 'world' |
45 | 44 |
|
46 | | - def scale(self, transformation): |
47 | | - """Scales the collision mesh. |
| 45 | + def scale(self, scale_factor): |
| 46 | + """Scales the collision mesh uniformly. |
48 | 47 |
|
49 | 48 | Parameters |
50 | 49 | ---------- |
51 | | - transformation : compas.geometry.Scale |
| 50 | + scale_factor : :obj:`float` |
| 51 | + Scale factor. |
52 | 52 | """ |
53 | | - mesh_transform(self.mesh, transformation) |
| 53 | + S = Scale([scale_factor] * 3) |
| 54 | + self.mesh.transform(S) |
54 | 55 |
|
55 | 56 |
|
56 | 57 | class AttachedCollisionMesh(object): |
@@ -140,8 +141,8 @@ def add_collision_mesh(self, collision_mesh, scale=False): |
140 | 141 | collision_mesh.root_name = self.robot.root_name |
141 | 142 |
|
142 | 143 | if scale: |
143 | | - S = Scale([1./self.robot.scale_factor] * 3) |
144 | | - collision_mesh.scale(S) |
| 144 | + scale_factor = 1. / self.robot.scale_factor |
| 145 | + collision_mesh.scale(scale_factor) |
145 | 146 |
|
146 | 147 | self.client.add_collision_mesh(collision_mesh) |
147 | 148 |
|
@@ -194,8 +195,8 @@ def append_collision_mesh(self, collision_mesh, scale=False): |
194 | 195 | collision_mesh.root_name = self.robot.root_name |
195 | 196 |
|
196 | 197 | if scale: |
197 | | - S = Scale([1./self.robot.scale_factor] * 3) |
198 | | - collision_mesh.scale(S) |
| 198 | + scale_factor = 1. / self.robot.scale_factor |
| 199 | + collision_mesh.scale(scale_factor) |
199 | 200 |
|
200 | 201 | self.robot.client.append_collision_mesh(collision_mesh) |
201 | 202 |
|
@@ -226,8 +227,8 @@ def add_attached_collision_mesh(self, attached_collision_mesh, scale=False): |
226 | 227 | self.ensure_client() |
227 | 228 |
|
228 | 229 | if scale: |
229 | | - S = Scale([1./self.robot.scale_factor] * 3) |
230 | | - attached_collision_mesh.collision_mesh.scale(S) |
| 230 | + scale_factor = 1. / self.robot.scale_factor |
| 231 | + attached_collision_mesh.collision_mesh.scale(scale_factor) |
231 | 232 |
|
232 | 233 | self.client.add_attached_collision_mesh(attached_collision_mesh) |
233 | 234 |
|
@@ -293,8 +294,8 @@ def attach_collision_mesh_to_robot_end_effector(self, collision_mesh, scale=Fals |
293 | 294 | self.ensure_client() |
294 | 295 |
|
295 | 296 | if scale: |
296 | | - S = Scale([1./self.robot.scale_factor] * 3) |
297 | | - collision_mesh.scale(S) |
| 297 | + scale_factor = 1. / self.robot.scale_factor |
| 298 | + collision_mesh.scale(scale_factor) |
298 | 299 |
|
299 | 300 | ee_link_name = self.robot.get_end_effector_link_name(group) |
300 | 301 | touch_links = [ee_link_name] |
|
0 commit comments