Skip to content

Commit

Permalink
bug fix try no. 2
Browse files Browse the repository at this point in the history
Build 3.8 to Build 3.10 throw the following error:

FAILED tests/test_grippers.py::TestGrippers::test_grippers - AssertionError: False is not true
  • Loading branch information
philipp1604 committed Jun 3, 2024
1 parent f1951da commit ae44f51
Showing 1 changed file with 9 additions and 1 deletion.
10 changes: 9 additions & 1 deletion tests/test_g_code_logger.py
Original file line number Diff line number Diff line change
Expand Up @@ -87,10 +87,18 @@ def test_uppdate_g_code(self):
# cameraDistance=2.0, cameraYaw=50.0,
# cameraPitch=-30,
# cameraTargetPosition=np.array([1.9, 0, 1]) + start_pos)
p.setPhysicsEngineParameter(numSolverIterations=10000)

p.configureDebugVisualizer(p.COV_ENABLE_GUI, 0)
p.setPhysicsEngineParameter(numSolverIterations=5000)
p.setPhysicsEngineParameter(numSolverIterations=10000)

p.setAdditionalSearchPath(pybullet_data.getDataPath())
p.setAdditionalSearchPath(pybullet_data.getDataPath())

p.setGravity(0, 0, -10)
p.createCollisionShape(p.GEOM_MESH,
fileName="samurai_monastry.obj",
flags=p.GEOM_FORCE_CONCAVE_TRIMESH)
# p.loadURDF(urdf_fofa, useFixedBase=True, globalScaling=0.001)
# Setting up robot position
test_robot = pi.RobotBase(urdf_robot, start_pos, start_orientation)
Expand Down

0 comments on commit ae44f51

Please sign in to comment.