fix pybullet racecarGymEnv to use thread-safe pybullet
This commit is contained in:
@@ -1,24 +1,24 @@
|
||||
import os
|
||||
import pybullet as p
|
||||
import numpy as np
|
||||
import copy
|
||||
import math
|
||||
|
||||
class Racecar:
|
||||
|
||||
def __init__(self, urdfRootPath='', timeStep=0.01):
|
||||
def __init__(self, bullet_client, urdfRootPath='', timeStep=0.01):
|
||||
self.urdfRootPath = urdfRootPath
|
||||
self.timeStep = timeStep
|
||||
self._p = bullet_client
|
||||
self.reset()
|
||||
|
||||
def reset(self):
|
||||
self.racecarUniqueId = p.loadURDF(os.path.join(os.path.dirname(__file__),"../data","racecar/racecar.urdf"), [0,0,.2])
|
||||
self.racecarUniqueId = self._p.loadURDF(os.path.join(os.path.dirname(__file__),"../data","racecar/racecar.urdf"), [0,0,.2])
|
||||
self.maxForce = 20
|
||||
self.nMotors = 2
|
||||
self.motorizedwheels=[2]
|
||||
self.inactiveWheels = [3,5,7]
|
||||
for wheel in self.inactiveWheels:
|
||||
p.setJointMotorControl2(self.racecarUniqueId,wheel,p.VELOCITY_CONTROL,targetVelocity=0,force=0)
|
||||
self._p.setJointMotorControl2(self.racecarUniqueId,wheel,self._p.VELOCITY_CONTROL,targetVelocity=0,force=0)
|
||||
|
||||
self.motorizedWheels = [2]
|
||||
self.steeringLinks=[4,6]
|
||||
@@ -33,7 +33,7 @@ class Racecar:
|
||||
|
||||
def getObservation(self):
|
||||
observation = []
|
||||
pos,orn=p.getBasePositionAndOrientation(self.racecarUniqueId)
|
||||
pos,orn=self._p.getBasePositionAndOrientation(self.racecarUniqueId)
|
||||
|
||||
observation.extend(list(pos))
|
||||
observation.extend(list(orn))
|
||||
@@ -52,7 +52,7 @@ class Racecar:
|
||||
|
||||
|
||||
for motor in self.motorizedwheels:
|
||||
p.setJointMotorControl2(self.racecarUniqueId,motor,p.VELOCITY_CONTROL,targetVelocity=targetVelocity,force=self.maxForce)
|
||||
self._p.setJointMotorControl2(self.racecarUniqueId,motor,self._p.VELOCITY_CONTROL,targetVelocity=targetVelocity,force=self.maxForce)
|
||||
for steer in self.steeringLinks:
|
||||
p.setJointMotorControl2(self.racecarUniqueId,steer,p.POSITION_CONTROL,targetPosition=steeringAngle)
|
||||
self._p.setJointMotorControl2(self.racecarUniqueId,steer,self._p.POSITION_CONTROL,targetPosition=steeringAngle)
|
||||
|
||||
|
||||
Reference in New Issue
Block a user