allow to use colors from MJCF file as option (default to random Google colors), use p.loadMJCF(filename, flags=p.URDF_MJCF_COLORS_FROM_FILE
fix quadruped.py example. add PyBullet.isConnected() API, more friendly than PyBullet.getConnectionInfo()["connected"]
This commit is contained in:
@@ -4,7 +4,10 @@ import math
|
||||
|
||||
|
||||
def drawInertiaBox(parentUid, parentLinkIndex, color):
|
||||
mass,frictionCoeff, inertia =p.getDynamicsInfo(bodyUniqueId=parentUid,linkIndex=parentLinkIndex, flags = p.DYNAMICS_INFO_REPORT_INERTIA)
|
||||
dyn = p.getDynamicsInfo(parentUid, parentLinkIndex)
|
||||
mass=dyn[0]
|
||||
frictionCoeff=dyn[1]
|
||||
inertia = dyn[2]
|
||||
if (mass>0):
|
||||
Ixx = inertia[0]
|
||||
Iyy = inertia[1]
|
||||
@@ -79,7 +82,7 @@ p.setTimeStep(fixedTimeStep)
|
||||
|
||||
orn = p.getQuaternionFromEuler([0,0,0.4])
|
||||
p.setRealTimeSimulation(0)
|
||||
quadruped = p.loadURDF("quadruped/minitaur_v1.urdf",[1,-1,.3],orn,useFixedBase=False, useMaximalCoordinates=useMaximalCoordinates)
|
||||
quadruped = p.loadURDF("quadruped/minitaur_v1.urdf",[1,-1,.3],orn,useFixedBase=False, useMaximalCoordinates=useMaximalCoordinates, flags=p.URDF_USE_IMPLICIT_CYLINDER)
|
||||
nJoints = p.getNumJoints(quadruped)
|
||||
|
||||
jointNameToId = {}
|
||||
@@ -123,7 +126,11 @@ halfpi = 1.57079632679
|
||||
twopi = 4*halfpi
|
||||
kneeangle = -2.1834
|
||||
|
||||
mass, friction, localInertiaDiagonal = p.getDynamicsInfo(quadruped,-1, flags=p.DYNAMICS_INFO_REPORT_INERTIA )
|
||||
dyn = p.getDynamicsInfo(quadruped,-1)
|
||||
mass=dyn[0]
|
||||
friction=dyn[1]
|
||||
localInertiaDiagonal = dyn[2]
|
||||
|
||||
print("localInertiaDiagonal",localInertiaDiagonal)
|
||||
|
||||
#this is a no-op, just to show the API
|
||||
|
||||
@@ -526,6 +526,33 @@ void b3pybulletExitFunc(void)
|
||||
}
|
||||
}
|
||||
|
||||
static PyObject* pybullet_isConnected(PyObject* self, PyObject* args, PyObject* keywds)
|
||||
{
|
||||
int physicsClientId = 0;
|
||||
int isConnected = 0;
|
||||
int method = 0;
|
||||
PyObject* pylist = 0;
|
||||
PyObject* val = 0;
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
static char* kwlist[] = { "physicsClientId", NULL };
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|i", kwlist, &physicsClientId))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
sm = getPhysicsClient(physicsClientId);
|
||||
if (sm != 0)
|
||||
{
|
||||
if (b3CanSubmitCommand(sm))
|
||||
{
|
||||
isConnected = 1;
|
||||
method = sPhysicsClientsGUI[physicsClientId];
|
||||
}
|
||||
}
|
||||
|
||||
return PyLong_FromLong(isConnected);
|
||||
}
|
||||
|
||||
|
||||
|
||||
static PyObject* pybullet_getConnectionInfo(PyObject* self, PyObject* args, PyObject* keywds)
|
||||
{
|
||||
@@ -8249,6 +8276,10 @@ static PyMethodDef SpamMethods[] = {
|
||||
"getConnectionInfo(physicsClientId=0)\n"
|
||||
"Return if a given client id is connected, and using what method."},
|
||||
|
||||
{ "isConnected", (PyCFunction)pybullet_isConnected, METH_VARARGS | METH_KEYWORDS,
|
||||
"isConnected(physicsClientId=0)\n"
|
||||
"Return if a given client id is connected." },
|
||||
|
||||
{"resetSimulation", (PyCFunction)pybullet_resetSimulation, METH_VARARGS | METH_KEYWORDS,
|
||||
"resetSimulation(physicsClientId=0)\n"
|
||||
"Reset the simulation: remove all objects and start from an empty world."},
|
||||
@@ -8818,7 +8849,8 @@ initpybullet(void)
|
||||
PyModule_AddIntConstant(m, "URDF_USE_INERTIA_FROM_FILE", URDF_USE_INERTIA_FROM_FILE);
|
||||
PyModule_AddIntConstant(m, "URDF_USE_IMPLICIT_CYLINDER", URDF_USE_IMPLICIT_CYLINDER);
|
||||
PyModule_AddIntConstant(m, "URDF_GLOBAL_VELOCITIES_MB", URDF_GLOBAL_VELOCITIES_MB);
|
||||
|
||||
PyModule_AddIntConstant(m, "MJCF_COLORS_FROM_FILE", MJCF_COLORS_FROM_FILE);
|
||||
|
||||
PyModule_AddIntConstant(m, "URDF_USE_SELF_COLLISION", URDF_USE_SELF_COLLISION);
|
||||
PyModule_AddIntConstant(m, "URDF_USE_SELF_COLLISION_EXCLUDE_PARENT", URDF_USE_SELF_COLLISION_EXCLUDE_PARENT);
|
||||
PyModule_AddIntConstant(m, "URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS", URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS);
|
||||
|
||||
Reference in New Issue
Block a user