diff options
author | jingyuc <chenjy@g.ucla.edu> | 2022-02-28 01:04:14 -0800 |
---|---|---|
committer | jingyuc <chenjy@g.ucla.edu> | 2022-02-28 01:04:14 -0800 |
commit | c89a7054e9afe693e2237158d253242d7e2ab3f2 (patch) | |
tree | d8c1a48638336194379245c6c978cdbf286a4355 | |
parent | 41ce1cca2458d687c74cd3a4aad4054ba922ada1 (diff) | |
download | bullet3-c89a7054e9afe693e2237158d253242d7e2ab3f2.tar.gz |
pybullet reduced deformable examples setup updated
-rw-r--r-- | examples/RobotSimulator/RobotSimulatorMain.cpp | 22 | ||||
-rw-r--r-- | examples/pybullet/examples/reduced_deformable_cube.py | 5 | ||||
-rw-r--r-- | examples/pybullet/examples/reduced_deformable_torus.py | 11 |
3 files changed, 32 insertions, 6 deletions
diff --git a/examples/RobotSimulator/RobotSimulatorMain.cpp b/examples/RobotSimulator/RobotSimulatorMain.cpp index fd83fd02f..497bcfcda 100644 --- a/examples/RobotSimulator/RobotSimulatorMain.cpp +++ b/examples/RobotSimulator/RobotSimulatorMain.cpp @@ -62,6 +62,28 @@ int main(int argc, char* argv[]) } { + int cubeID = sim->loadURDF("cube.urdf"); + btVector3 basePosition = btVector3(2, 0, 2); + btQuaternion baseOrientation = btQuaternion(0, 0, 0, 1); + sim->resetBasePositionAndOrientation(cubeID, basePosition, baseOrientation); + } + + { + int deformableUID = sim->loadURDF("reduced_torus/reduced_torus.urdf"); + // int deformableUID = sim->loadURDF("reduced_cube/reduced_cube.urdf"); + // int deformableUID = sim->loadURDF("reduced_bottle/reduced_bottle.urdf"); + // int deformableUID = sim->loadURDF("reduced_bottle_coarse/reduced_bottle_coarse.urdf"); + // int deformableUID = sim->loadURDF("reduced_bottle/deform_bottle.urdf"); + // int deformableUID = sim->loadURDF("torus_deform.urdf"); + btVector3 basePosition = btVector3(3, 3, 3); + // btVector3 basePosition = btVector3(0, 0, 0.2); + // btVector3 basePosition = btVector3(0, 0.5, 0.2); + btQuaternion baseOrientation = btQuaternion(0, 0, 0, 1); + // btQuaternion baseOrientation = btQuaternion(btVector3(1, 0, 0), SIMD_PI / 2.0); + sim->resetBasePositionAndOrientation(deformableUID, basePosition, baseOrientation); + } + + { // int deformableUID = sim->loadURDF("reduced_torus/reduced_torus.urdf"); int deformableUID = sim->loadURDF("reduced_cube/reduced_cube.urdf"); // int deformableUID = sim->loadURDF("reduced_bottle/reduced_bottle.urdf"); diff --git a/examples/pybullet/examples/reduced_deformable_cube.py b/examples/pybullet/examples/reduced_deformable_cube.py index 87b5fd44f..cab91cfdb 100644 --- a/examples/pybullet/examples/reduced_deformable_cube.py +++ b/examples/pybullet/examples/reduced_deformable_cube.py @@ -6,7 +6,6 @@ physicsClient = p.connect(p.GUI) p.setAdditionalSearchPath(pybullet_data.getDataPath()) -# p.resetSimulation(p.RESET_USE_DEFORMABLE_WORLD) p.resetSimulation(p.RESET_USE_REDUCED_DEFORMABLE_WORLD) p.resetDebugVisualizerCamera(4,-40,-30,[0, 0, 0]) p.setGravity(0, 0, -10) @@ -14,9 +13,9 @@ p.setGravity(0, 0, -10) tex = p.loadTexture("uvmap.png") planeId = p.loadURDF("plane.urdf", [0,0,-2]) -boxId = p.loadURDF("cube.urdf", [1,1,10],useMaximalCoordinates = True) +boxId = p.loadURDF("cube.urdf", [1,1,5],useMaximalCoordinates = True) -p.startStateLogging(p.STATE_LOGGING_VIDEO_MP4, "reduced_cube.mp4") +#p.startStateLogging(p.STATE_LOGGING_VIDEO_MP4, "reduced_cube.mp4") cube = p.loadURDF("reduced_cube/reduced_cube.urdf", [1,1,1]) p.changeVisualShape(cube, -1, rgbaColor=[1,1,1,1], textureUniqueId=tex, flags=0) p.setPhysicsEngineParameter(sparseSdfVoxelSize=0.25) diff --git a/examples/pybullet/examples/reduced_deformable_torus.py b/examples/pybullet/examples/reduced_deformable_torus.py index ce145b264..8f42e0372 100644 --- a/examples/pybullet/examples/reduced_deformable_torus.py +++ b/examples/pybullet/examples/reduced_deformable_torus.py @@ -13,11 +13,16 @@ p.setGravity(0, 0, -10) tex = p.loadTexture("uvmap.png") planeId = p.loadURDF("plane.urdf", [0,0,-2]) -boxId = p.loadURDF("cube.urdf", [1,1,3],useMaximalCoordinates = True) +box1 = p.loadURDF("cube.urdf", [1,1,3],useMaximalCoordinates = True) +box2 = p.loadURDF("cube.urdf", [0,3,2],useMaximalCoordinates = True) # p.startStateLogging(p.STATE_LOGGING_VIDEO_MP4, "reduced_torus.mp4") -cube = p.loadURDF("reduced_torus/reduced_torus.urdf", [1,1,1]) -p.changeVisualShape(cube, -1, rgbaColor=[1,1,1,1], textureUniqueId=tex, flags=0) +reduced_obj1= p.loadURDF("reduced_torus/reduced_torus.urdf", [1,1,1]) +p.changeVisualShape(reduced_obj1, -1, rgbaColor=[1,1,1,1], textureUniqueId=tex, flags=0) + +reduced_obj2 = p.loadURDF("reduced_torus/reduced_torus.urdf", [1,2,1]) +p.changeVisualShape(reduced_obj2, -1, rgbaColor=[1,1,1,1], textureUniqueId=tex, flags=0) + p.setPhysicsEngineParameter(sparseSdfVoxelSize=0.25) p.setRealTimeSimulation(0) |