Allow to configure Y=up, default is Z=up, using pybullet.configureDebugVisualizer(COV_ENABLE_Y_AXIS_UP,0/1)
Implement pybullet.getConnectionInfo, returns [isConnected, connectionMethod], where isConnected=0 or 1
This commit is contained in:
@@ -377,6 +377,13 @@ void OpenGLExampleBrowser::registerFileImporter(const char* extension, CommonExa
|
|||||||
|
|
||||||
void OpenGLExampleBrowserVisualizerFlagCallback(int flag, bool enable)
|
void OpenGLExampleBrowserVisualizerFlagCallback(int flag, bool enable)
|
||||||
{
|
{
|
||||||
|
if (flag == COV_ENABLE_Y_AXIS_UP)
|
||||||
|
{
|
||||||
|
//either Y = up or Z
|
||||||
|
int upAxis = enable? 1:2;
|
||||||
|
s_app->setUpAxis(upAxis);
|
||||||
|
}
|
||||||
|
|
||||||
if (flag == COV_ENABLE_RENDERING)
|
if (flag == COV_ENABLE_RENDERING)
|
||||||
{
|
{
|
||||||
gEnableRenderLoop = (enable!=0);
|
gEnableRenderLoop = (enable!=0);
|
||||||
|
|||||||
@@ -323,10 +323,8 @@ B3_SHARED_API int b3GetStatusJacobian(b3SharedMemoryStatusHandle statusHandle,
|
|||||||
double* angularJacobian);
|
double* angularJacobian);
|
||||||
|
|
||||||
B3_SHARED_API b3SharedMemoryCommandHandle b3CalculateMassMatrixCommandInit(b3PhysicsClientHandle physClient, int bodyIndex, const double* jointPositionsQ);
|
B3_SHARED_API b3SharedMemoryCommandHandle b3CalculateMassMatrixCommandInit(b3PhysicsClientHandle physClient, int bodyIndex, const double* jointPositionsQ);
|
||||||
B3_SHARED_API int b3GetStatusMassMatrix(b3SharedMemoryStatusHandle statusHandle,
|
///the mass matrix is stored in column-major layout of size dofCount*dofCount
|
||||||
int* dofCount,
|
B3_SHARED_API int b3GetStatusMassMatrix(b3PhysicsClientHandle physClient, b3SharedMemoryStatusHandle statusHandle, int* dofCount, double* massMatrix);
|
||||||
double* massMatrix);
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
///compute the joint positions to move the end effector to a desired target using inverse kinematics
|
///compute the joint positions to move the end effector to a desired target using inverse kinematics
|
||||||
|
|||||||
@@ -376,10 +376,16 @@ void MyKeyboardCallback(int key, int state)
|
|||||||
extern bool useShadowMap;
|
extern bool useShadowMap;
|
||||||
static bool gEnableVRRenderControllers=true;
|
static bool gEnableVRRenderControllers=true;
|
||||||
static bool gEnableVRRendering = true;
|
static bool gEnableVRRendering = true;
|
||||||
|
static int gUpAxis = 2;
|
||||||
|
|
||||||
void VRPhysicsServerVisualizerFlagCallback(int flag, bool enable)
|
void VRPhysicsServerVisualizerFlagCallback(int flag, bool enable)
|
||||||
{
|
{
|
||||||
|
if (flag == COV_ENABLE_Y_AXIS_UP)
|
||||||
|
{
|
||||||
|
//either Y = up or Z
|
||||||
|
gUpAxis = enable? 1:2;
|
||||||
|
}
|
||||||
|
|
||||||
if (flag == COV_ENABLE_SHADOWS)
|
if (flag == COV_ENABLE_SHADOWS)
|
||||||
{
|
{
|
||||||
useShadowMap = enable;
|
useShadowMap = enable;
|
||||||
@@ -890,6 +896,7 @@ void CMainApplication::RunMainLoop()
|
|||||||
|
|
||||||
while ( !bQuit && !m_app->m_window->requestedExit())
|
while ( !bQuit && !m_app->m_window->requestedExit())
|
||||||
{
|
{
|
||||||
|
this->m_app->setUpAxis(gUpAxis);
|
||||||
b3ChromeUtilsEnableProfiling();
|
b3ChromeUtilsEnableProfiling();
|
||||||
if (gEnableVRRendering)
|
if (gEnableVRRendering)
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -503,6 +503,36 @@ void b3pybulletExitFunc(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
static PyObject* pybullet_getConnectionInfo(PyObject* self, PyObject* args, PyObject* keywds)
|
||||||
|
{
|
||||||
|
int physicsClientId = 0;
|
||||||
|
int isConnected=0;
|
||||||
|
int method=0;
|
||||||
|
PyObject* pylist = 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];
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
pylist = PyTuple_New(2);
|
||||||
|
PyTuple_SetItem(pylist, 0, PyInt_FromLong(isConnected));
|
||||||
|
PyTuple_SetItem(pylist, 1, PyInt_FromLong(method));
|
||||||
|
return pylist;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
static PyObject* pybullet_saveWorld(PyObject* self, PyObject* args, PyObject* keywds)
|
static PyObject* pybullet_saveWorld(PyObject* self, PyObject* args, PyObject* keywds)
|
||||||
{
|
{
|
||||||
const char* worldFileName = "";
|
const char* worldFileName = "";
|
||||||
@@ -7314,13 +7344,14 @@ static PyObject* pybullet_calculateMassMatrix(PyObject* self, PyObject* args, Py
|
|||||||
if (statusType == CMD_CALCULATED_MASS_MATRIX_COMPLETED)
|
if (statusType == CMD_CALCULATED_MASS_MATRIX_COMPLETED)
|
||||||
{
|
{
|
||||||
int dofCount;
|
int dofCount;
|
||||||
b3GetStatusMassMatrix(statusHandle, &dofCount, NULL);
|
b3GetStatusMassMatrix(sm, statusHandle, &dofCount, NULL);
|
||||||
if (dofCount)
|
if (dofCount)
|
||||||
{
|
{
|
||||||
pyResultList = PyTuple_New(dofCount);
|
|
||||||
int byteSizeDofCount = sizeof(double) * dofCount;
|
int byteSizeDofCount = sizeof(double) * dofCount;
|
||||||
|
pyResultList = PyTuple_New(dofCount);
|
||||||
|
|
||||||
massMatrix = (double*)malloc(dofCount * byteSizeDofCount);
|
massMatrix = (double*)malloc(dofCount * byteSizeDofCount);
|
||||||
b3GetStatusMassMatrix(statusHandle, NULL, massMatrix);
|
b3GetStatusMassMatrix(sm, statusHandle, NULL, massMatrix);
|
||||||
if (massMatrix)
|
if (massMatrix)
|
||||||
{
|
{
|
||||||
int r;
|
int r;
|
||||||
@@ -7372,6 +7403,10 @@ static PyMethodDef SpamMethods[] = {
|
|||||||
"disconnect(physicsClientId=0)\n"
|
"disconnect(physicsClientId=0)\n"
|
||||||
"Disconnect from the physics server."},
|
"Disconnect from the physics server."},
|
||||||
|
|
||||||
|
{"getConnectionInfo", (PyCFunction)pybullet_getConnectionInfo, METH_VARARGS | METH_KEYWORDS,
|
||||||
|
"getConnectionInfo(physicsClientId=0)\n"
|
||||||
|
"Return if a given client id is connected, and using what method."},
|
||||||
|
|
||||||
{"resetSimulation", (PyCFunction)pybullet_resetSimulation, METH_VARARGS | METH_KEYWORDS,
|
{"resetSimulation", (PyCFunction)pybullet_resetSimulation, METH_VARARGS | METH_KEYWORDS,
|
||||||
"resetSimulation(physicsClientId=0)\n"
|
"resetSimulation(physicsClientId=0)\n"
|
||||||
"Reset the simulation: remove all objects and start from an empty world."},
|
"Reset the simulation: remove all objects and start from an empty world."},
|
||||||
|
|||||||
Reference in New Issue
Block a user