summaryrefslogtreecommitdiff
path: root/examples/pybullet/gym/pybullet_utils
diff options
context:
space:
mode:
authorErwin Coumans <erwincoumans@erwincoumans-macbookpro2.roam.corp.google.com>2018-04-12 14:01:17 -0700
committerErwin Coumans <erwincoumans@erwincoumans-macbookpro2.roam.corp.google.com>2018-04-12 14:01:17 -0700
commitfcce77fe497c1ef4c1177e101af009d2c99d0176 (patch)
tree20794e3c6110400e65ca777ebe9e7c67b8870cbe /examples/pybullet/gym/pybullet_utils
parent391b0e4061d8d5518689978be63d43f84d429670 (diff)
downloadbullet3-fcce77fe497c1ef4c1177e101af009d2c99d0176.tar.gz
fix spaces/tab issue in urdfEditor.py
Diffstat (limited to 'examples/pybullet/gym/pybullet_utils')
-rw-r--r--examples/pybullet/gym/pybullet_utils/urdfEditor.py37
1 files changed, 13 insertions, 24 deletions
diff --git a/examples/pybullet/gym/pybullet_utils/urdfEditor.py b/examples/pybullet/gym/pybullet_utils/urdfEditor.py
index 9cfd950ed..ee1a2278a 100644
--- a/examples/pybullet/gym/pybullet_utils/urdfEditor.py
+++ b/examples/pybullet/gym/pybullet_utils/urdfEditor.py
@@ -375,8 +375,8 @@ class UrdfEditor(object):
physicsClientId=physicsClientId)
- urdfVisuals = base.urdf_visual_shapes
- baseVisualShapeIndex = p.createVisualShapeArray(shapeTypes=[v.geom_type for v in urdfVisuals],
+ urdfVisuals = base.urdf_visual_shapes
+ baseVisualShapeIndex = p.createVisualShapeArray(shapeTypes=[v.geom_type for v in urdfVisuals],
halfExtents=[[ext * 0.5 for ext in v.geom_extents] for v in urdfVisuals],
radii=[v.geom_radius for v in urdfVisuals],
lengths=[v.geom_length[0] for v in urdfVisuals],
@@ -453,28 +453,17 @@ class UrdfEditor(object):
collisionFrameOrientations=linkOrientationsArray,
physicsClientId=physicsClientId)
- urdfVisuals = link.urdf_visual_shapes
- linkVisualShapeIndex = p.createVisualShapeArray(shapeTypes=[v.geom_type for v in urdfVisuals],
- halfExtents=[[ext * 0.5 for ext in v.geom_extents] for v in urdfVisuals],
- radii=[v.geom_radius for v in urdfVisuals],
- lengths=[v.geom_length[0] for v in urdfVisuals],
- fileNames=[v.geom_meshfilename for v in urdfVisuals],
- meshScales=[v.geom_meshscale for v in urdfVisuals],
- rgbaColors=[v.material_rgba for v in urdfVisuals],
- visualFramePositions=[v.origin_xyz for v in urdfVisuals],
- visualFrameOrientations=[v.origin_rpy for v in urdfVisuals],
- physicsClientId=physicsClientId)
-
-# linkVisualShapeIndex = p.createVisualShape(shapeType=urdfVisual.geom_type,
-# halfExtents=[ext * 0.5 for ext in urdfVisual.geom_extents],
-# radius=urdfVisual.geom_radius,
-# length=urdfVisual.geom_length[0],
-# fileName=urdfVisual.geom_meshfilename,
-# meshScale=urdfVisual.geom_meshscale,
-# rgbaColor=urdfVisual.material_rgba,
-# visualFramePosition=urdfVisual.origin_xyz,
-# visualFrameOrientation=urdfVisual.origin_rpy,
-# physicsClientId=physicsClientId)
+ urdfVisuals = link.urdf_visual_shapes
+ linkVisualShapeIndex = p.createVisualShapeArray(shapeTypes=[v.geom_type for v in urdfVisuals],
+ halfExtents=[[ext * 0.5 for ext in v.geom_extents] for v in urdfVisuals],
+ radii=[v.geom_radius for v in urdfVisuals],
+ lengths=[v.geom_length[0] for v in urdfVisuals],
+ fileNames=[v.geom_meshfilename for v in urdfVisuals],
+ meshScales=[v.geom_meshscale for v in urdfVisuals],
+ rgbaColors=[v.material_rgba for v in urdfVisuals],
+ visualFramePositions=[v.origin_xyz for v in urdfVisuals],
+ visualFrameOrientations=[v.origin_rpy for v in urdfVisuals],
+ physicsClientId=physicsClientId)
linkMasses.append(linkMass)
linkCollisionShapeIndices.append(linkCollisionShapeIndex)