more fixes in pybullet_gym envs/data.
implement pybullet.setAdditionalSearchPath
This commit is contained in:
@@ -1,4 +1,13 @@
|
||||
import os, inspect
|
||||
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||
print ("current_dir=" + currentdir)
|
||||
parentdir = os.path.join(currentdir,"../gym")
|
||||
|
||||
os.sys.path.insert(0,parentdir)
|
||||
|
||||
import pybullet as p
|
||||
import pybullet_data
|
||||
|
||||
import time
|
||||
|
||||
cid = p.connect(p.SHARED_MEMORY)
|
||||
@@ -14,9 +23,9 @@ useRealTimeSim = 1
|
||||
#p.startStateLogging(p.STATE_LOGGING_VIDEO_MP4, "racecar.mp4")
|
||||
p.setRealTimeSimulation(useRealTimeSim) # either this
|
||||
#p.loadURDF("plane.urdf")
|
||||
p.loadSDF("stadium.sdf")
|
||||
p.loadSDF(os.path.join(pybullet_data.getDataPath(),"stadium.sdf"))
|
||||
|
||||
car = p.loadURDF("racecar/racecar.urdf")
|
||||
car = p.loadURDF(os.path.join(pybullet_data.getDataPath(),"racecar/racecar.urdf"))
|
||||
for i in range (p.getNumJoints(car)):
|
||||
print (p.getJointInfo(car,i))
|
||||
|
||||
|
||||
@@ -1,16 +1,27 @@
|
||||
#os.sys.path.insert is only needed when pybullet is not installed
|
||||
#but running from github repo instead
|
||||
import os, inspect
|
||||
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||
print ("current_dir=" + currentdir)
|
||||
parentdir = os.path.join(currentdir,"../gym")
|
||||
os.sys.path.insert(0,parentdir)
|
||||
|
||||
|
||||
import pybullet
|
||||
import pybullet_data
|
||||
|
||||
import time
|
||||
|
||||
#choose connection method: GUI, DIRECT, SHARED_MEMORY
|
||||
pybullet.connect(pybullet.GUI)
|
||||
pybullet.loadURDF("plane.urdf",0,0,-1)
|
||||
pybullet.loadURDF(os.path.join(pybullet_data.getDataPath(),"plane.urdf"),0,0,-1)
|
||||
#load URDF, given a relative or absolute file+path
|
||||
obj = pybullet.loadURDF("r2d2.urdf")
|
||||
obj = pybullet.loadURDF(os.path.join(pybullet_data.getDataPath(),"r2d2.urdf"))
|
||||
|
||||
posX=0
|
||||
posY=3
|
||||
posZ=2
|
||||
obj2 = pybullet.loadURDF("kuka_lwr/kuka.urdf",posX,posY,posZ)
|
||||
obj2 = pybullet.loadURDF(os.path.join(pybullet_data.getDataPath(),"kuka_iiwa/model.urdf"),posX,posY,posZ)
|
||||
|
||||
#query the number of joints of the object
|
||||
numJoints = pybullet.getNumJoints(obj)
|
||||
|
||||
@@ -2,10 +2,10 @@
|
||||
Classic cart-pole system implemented by Rich Sutton et al.
|
||||
Copied from https://webdocs.cs.ualberta.ca/~sutton/book/code/pole.c
|
||||
"""
|
||||
import os, inspect
|
||||
import os, inspect
|
||||
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||
print ("current_dir=" + currentdir)
|
||||
os.sys.path.insert(0,currentdir)
|
||||
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||
os.sys.path.insert(0,parentdir)
|
||||
|
||||
import logging
|
||||
import math
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
import os, inspect
|
||||
import os, inspect
|
||||
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||
print ("current_dir=" + currentdir)
|
||||
os.sys.path.insert(0,currentdir)
|
||||
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||
os.sys.path.insert(0,parentdir)
|
||||
|
||||
import pybullet as p
|
||||
import numpy as np
|
||||
|
||||
@@ -1,7 +1,8 @@
|
||||
import os, inspect
|
||||
import os, inspect
|
||||
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||
print ("current_dir=" + currentdir)
|
||||
os.sys.path.insert(0,currentdir)
|
||||
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||
os.sys.path.insert(0,parentdir)
|
||||
|
||||
|
||||
import math
|
||||
import gym
|
||||
|
||||
@@ -1,4 +1,3 @@
|
||||
import os
|
||||
import os, inspect
|
||||
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||
|
||||
@@ -1,8 +1,7 @@
|
||||
import os
|
||||
import os, inspect
|
||||
import os, inspect
|
||||
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||
print ("current_dir=" + currentdir)
|
||||
os.sys.path.insert(0,currentdir)
|
||||
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||
os.sys.path.insert(0,parentdir)
|
||||
|
||||
import math
|
||||
import gym
|
||||
|
||||
@@ -3,7 +3,7 @@ import gym, gym.spaces, gym.utils
|
||||
import numpy as np
|
||||
import os, inspect
|
||||
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||
parentdir = os.path.dirname(currentdir)
|
||||
os.sys.path.insert(0,parentdir)
|
||||
import pybullet_data
|
||||
|
||||
|
||||
@@ -1,11 +1,11 @@
|
||||
import os, inspect
|
||||
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
|
||||
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||
parentdir = os.path.dirname(currentdir)
|
||||
os.sys.path.insert(0,parentdir)
|
||||
import pybullet_data
|
||||
|
||||
|
||||
from .scene_abstract import Scene
|
||||
from pybullet_envs.scene_abstract import Scene
|
||||
import pybullet as p
|
||||
|
||||
|
||||
|
||||
@@ -3701,6 +3701,36 @@ static PyObject* pybullet_stopStateLogging(PyObject* self, PyObject* args, PyObj
|
||||
return Py_None;
|
||||
}
|
||||
|
||||
|
||||
static PyObject* pybullet_setAdditionalSearchPath(PyObject* self, PyObject* args, PyObject* keywds)
|
||||
{
|
||||
static char* kwlist[] = {"path", "physicsClientId", NULL};
|
||||
char* path = 0;
|
||||
int physicsClientId = 0;
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|i", kwlist,
|
||||
&path, &physicsClientId))
|
||||
return NULL;
|
||||
if (path)
|
||||
{
|
||||
b3SharedMemoryCommandHandle commandHandle;
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
|
||||
sm = getPhysicsClient(physicsClientId);
|
||||
if (sm == 0)
|
||||
{
|
||||
PyErr_SetString(SpamError, "Not connected to physics server.");
|
||||
return NULL;
|
||||
}
|
||||
commandHandle = b3SetAdditionalSearchPath(sm, path);
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
|
||||
}
|
||||
|
||||
Py_INCREF(Py_None);
|
||||
return Py_None;
|
||||
}
|
||||
|
||||
static PyObject* pybullet_setTimeOut(PyObject* self, PyObject* args, PyObject* keywds)
|
||||
{
|
||||
static char* kwlist[] = {"timeOutInSeconds", "physicsClientId", NULL};
|
||||
@@ -7215,6 +7245,10 @@ static PyMethodDef SpamMethods[] = {
|
||||
{"setTimeOut", (PyCFunction)pybullet_setTimeOut, METH_VARARGS | METH_KEYWORDS,
|
||||
"Set the timeOut in seconds, used for most of the API calls."},
|
||||
|
||||
{"setAdditionalSearchPath", (PyCFunction)pybullet_setAdditionalSearchPath,
|
||||
METH_VARARGS | METH_KEYWORDS,
|
||||
"Set an additional search path, used to load URDF/SDF files."},
|
||||
|
||||
{"getAPIVersion", (PyCFunction)pybullet_getAPIVersion,
|
||||
METH_VARARGS | METH_KEYWORDS,
|
||||
"Get version of the API. Compatibility exists for connections using the same API version. Make sure both client and server use the same number of bits (32-bit or 64bit)."},
|
||||
|
||||
Reference in New Issue
Block a user