add pybullet unittests.py with travis support
This commit is contained in:
@@ -10,6 +10,7 @@ addons:
|
||||
packages:
|
||||
- python3
|
||||
|
||||
|
||||
script:
|
||||
- echo "CXX="$CXX
|
||||
- echo "CC="$CC
|
||||
@@ -25,3 +26,5 @@ script:
|
||||
- make -j8
|
||||
- ctest -j8 --output-on-failure
|
||||
- sudo make install
|
||||
- sudo python3 setup.py install
|
||||
- python3 examples/pybullet/unittests/unittests.py
|
||||
|
||||
46
examples/pybullet/unittests/unittests.py
Normal file
46
examples/pybullet/unittests/unittests.py
Normal file
@@ -0,0 +1,46 @@
|
||||
import unittest
|
||||
import pybullet
|
||||
import time
|
||||
|
||||
class TestPybulletMethods(unittest.TestCase):
|
||||
|
||||
def test_import(self):
|
||||
import pybullet as p
|
||||
self.assertGreater(p.getAPIVersion(), 201700000)
|
||||
|
||||
def test_connect_direct(self):
|
||||
import pybullet as p
|
||||
cid = p.connect(p.DIRECT)
|
||||
self.assertEqual(cid,0)
|
||||
p.disconnect()
|
||||
|
||||
def test_loadurdf(self):
|
||||
import pybullet as p
|
||||
p.connect(p.DIRECT)
|
||||
ob = p.loadURDF("r2d2.urdf")
|
||||
self.assertEqual(ob,0)
|
||||
p.disconnect()
|
||||
|
||||
def test_rolling_friction(self):
|
||||
import pybullet as p
|
||||
p.connect(p.DIRECT)
|
||||
p.loadURDF("plane.urdf")
|
||||
sphere = p.loadURDF("sphere2.urdf",[0,0,1])
|
||||
p.resetBaseVelocity(sphere,linearVelocity=[1,0,0])
|
||||
p.changeDynamics(sphere,-1,linearDamping=0,angularDamping=0)
|
||||
#p.changeDynamics(sphere,-1,rollingFriction=0)
|
||||
p.setGravity(0,0,-10)
|
||||
for i in range (1000):
|
||||
p.stepSimulation()
|
||||
vel = p.getBaseVelocity(sphere)
|
||||
self.assertLess(vel[0][0],1e-10)
|
||||
self.assertLess(vel[0][1],1e-10)
|
||||
self.assertLess(vel[0][2],1e-10)
|
||||
self.assertLess(vel[1][0],1e-10)
|
||||
self.assertLess(vel[1][1],1e-10)
|
||||
self.assertLess(vel[1][2],1e-10)
|
||||
p.disconnect()
|
||||
|
||||
if __name__ == '__main__':
|
||||
unittest.main()
|
||||
|
||||
2
setup.py
2
setup.py
@@ -442,7 +442,7 @@ print("-----")
|
||||
|
||||
setup(
|
||||
name = 'pybullet',
|
||||
version='1.7.3',
|
||||
version='1.7.4',
|
||||
description='Official Python Interface for the Bullet Physics SDK specialized for Robotics Simulation and Reinforcement Learning',
|
||||
long_description='pybullet is an easy to use Python module for physics simulation, robotics and deep reinforcement learning based on the Bullet Physics SDK. With pybullet you can load articulated bodies from URDF, SDF and other file formats. pybullet provides forward dynamics simulation, inverse dynamics computation, forward and inverse kinematics and collision detection and ray intersection queries. Aside from physics simulation, pybullet supports to rendering, with a CPU renderer and OpenGL visualization and support for virtual reality headsets.',
|
||||
url='https://github.com/bulletphysics/bullet3',
|
||||
|
||||
Reference in New Issue
Block a user