mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-14 05:40:05 +00:00
Merge pull request #2781 from erwincoumans/master
bump up pybullet version to 2.7.5
This commit is contained in:
commit
bedf63c34d
@ -1049,7 +1049,7 @@ void PhysicsDirect::postProcessStatus(const struct SharedMemoryStatus& serverCmd
|
||||
|
||||
case CMD_REQUEST_OPENGL_VISUALIZER_CAMERA_FAILED:
|
||||
{
|
||||
b3Warning("requestOpenGLVisualizeCamera failed");
|
||||
//b3Warning("requestOpenGLVisualizeCamera failed");
|
||||
break;
|
||||
}
|
||||
case CMD_REMOVE_USER_CONSTRAINT_FAILED:
|
||||
|
@ -12709,6 +12709,8 @@ bool PhysicsServerCommandProcessor::processUpdateVisualShapeCommand(const struct
|
||||
m_data->m_guiHelper->changeSpecularColor(graphicsIndex, clientCmd.m_updateVisualShapeDataArguments.m_specularColor);
|
||||
}
|
||||
}
|
||||
#ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD
|
||||
|
||||
else if (bodyHandle->m_softBody)
|
||||
{
|
||||
if (clientCmd.m_updateFlags & CMD_UPDATE_VISUAL_SHAPE_RGBA_COLOR)
|
||||
@ -12720,6 +12722,7 @@ bool PhysicsServerCommandProcessor::processUpdateVisualShapeCommand(const struct
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -6980,7 +6980,27 @@ static PyObject* pybullet_getDebugVisualizerCamera(PyObject* self, PyObject* arg
|
||||
int hasCamInfo;
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
struct b3OpenGLVisualizerCameraInfo camera;
|
||||
PyObject* pyCameraList = 0;
|
||||
int i;
|
||||
camera.m_width=0;
|
||||
camera.m_height=0;
|
||||
camera.m_dist=0;
|
||||
camera.m_yaw=0;
|
||||
camera.m_pitch=0;
|
||||
|
||||
for (i=0;i<16;i++)
|
||||
{
|
||||
camera.m_viewMatrix[i]=0;
|
||||
camera.m_projectionMatrix[i]=0;
|
||||
}
|
||||
for (i=0;i<3;i++)
|
||||
{
|
||||
camera.m_camUp[i]=0;
|
||||
camera.m_camForward[i]=0;
|
||||
camera.m_horizontal[i]=0;
|
||||
camera.m_vertical[i]=0;
|
||||
camera.m_target[i]=0;
|
||||
}
|
||||
PyObject* pyCameraList = 0;
|
||||
|
||||
sm = getPhysicsClient(physicsClientId);
|
||||
if (sm == 0)
|
||||
@ -6993,7 +7013,7 @@ static PyObject* pybullet_getDebugVisualizerCamera(PyObject* self, PyObject* arg
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
|
||||
|
||||
hasCamInfo = b3GetStatusOpenGLVisualizerCamera(statusHandle, &camera);
|
||||
if (hasCamInfo)
|
||||
if (1)
|
||||
{
|
||||
PyObject* item = 0;
|
||||
pyCameraList = PyTuple_New(12);
|
||||
|
Loading…
Reference in New Issue
Block a user