add RacecarGymEnv as a gym experimentation environment
This commit is contained in:
@@ -5,8 +5,6 @@ useMaximalCoordinates = 0
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.loadSDF("stadium.sdf",useMaximalCoordinates=useMaximalCoordinates)
|
||||
p.setPhysicsEngineParameter(numSolverIterations=10)
|
||||
p.setPhysicsEngineParameter(fixedTimeStep=1./120.)
|
||||
sphereRadius = 0.05
|
||||
colSphereId = p.createCollisionShape(p.GEOM_SPHERE,radius=sphereRadius)
|
||||
colBoxId = p.createCollisionShape(p.GEOM_BOX,halfExtents=[sphereRadius,sphereRadius,sphereRadius])
|
||||
|
||||
@@ -20,7 +20,12 @@ car = p.loadURDF("racecar/racecar.urdf")
|
||||
for i in range (p.getNumJoints(car)):
|
||||
print (p.getJointInfo(car,i))
|
||||
|
||||
wheels = [2,3,5,7]
|
||||
inactive_wheels = [3,5,7]
|
||||
wheels = [2]
|
||||
|
||||
for wheel in inactive_wheels:
|
||||
p.setJointMotorControl2(car,wheel,p.VELOCITY_CONTROL,targetVelocity=0,force=0)
|
||||
|
||||
steering = [4,6]
|
||||
|
||||
targetVelocitySlider = p.addUserDebugParameter("wheelVelocity",-10,10,0)
|
||||
|
||||
Reference in New Issue
Block a user