Update to upstream
This commit is contained in:
21
examples/pybullet/examples/configureDebugVisualizer.py
Normal file
21
examples/pybullet/examples/configureDebugVisualizer.py
Normal file
@@ -0,0 +1,21 @@
|
||||
import pybullet as p
|
||||
import math
|
||||
import time
|
||||
dt = 1./240.
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.loadURDF("r2d2.urdf",[0,0,1])
|
||||
p.loadURDF("plane.urdf")
|
||||
p.setGravity(0,0,-10)
|
||||
|
||||
radius=5
|
||||
t = 0
|
||||
p.configureDebugVisualizer(shadowMapWorldSize=5)
|
||||
p.configureDebugVisualizer(shadowMapResolution=8192)
|
||||
|
||||
while (1):
|
||||
t+=dt
|
||||
p.configureDebugVisualizer(lightPosition=[radius*math.sin(t),radius*math.cos(t),3])
|
||||
|
||||
p.stepSimulation()
|
||||
time.sleep(dt)
|
||||
@@ -1,6 +1,5 @@
|
||||
# Blender v2.76 (sub 0) OBJ File: ''
|
||||
# www.blender.org
|
||||
mtllib l_link_mini.mtl
|
||||
o lower_link
|
||||
v -0.007927 -0.006511 0.072209
|
||||
v -0.007918 -0.006511 0.072209
|
||||
|
||||
@@ -4,7 +4,7 @@
|
||||
<inertial>
|
||||
<mass value="3.3"/>
|
||||
<origin xyz="0.0 0.0 0.0"/>
|
||||
<inertia ixx="0.011253" ixy="0" ixz="0" iyy="0.362030" iyz="0" izz="0.042673"/>
|
||||
<inertia ixx="0.011253" ixy="0" ixz="0" iyy="0.036203" iyz="0" izz="0.042673"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<geometry>
|
||||
|
||||
@@ -5869,15 +5869,18 @@ static PyObject* pybullet_getDebugVisualizerCamera(PyObject* self, PyObject* arg
|
||||
|
||||
static PyObject* pybullet_configureDebugVisualizer(PyObject* self, PyObject* args, PyObject* keywds)
|
||||
{
|
||||
int flag = 1;
|
||||
int flag = -1;
|
||||
int enable = -1;
|
||||
|
||||
int shadowMapResolution = -1;
|
||||
int shadowMapWorldSize = -1;
|
||||
int physicsClientId = 0;
|
||||
double remoteSyncTransformInterval = -1;
|
||||
PyObject* pyLightPosition = 0;
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
static char* kwlist[] = {"flag", "enable", "physicsClientId", NULL};
|
||||
static char* kwlist[] = {"flag", "enable", "lightPosition", "shadowMapResolution", "shadowMapWorldSize", "remoteSyncTransformInterval", "physicsClientId", NULL};
|
||||
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|i", kwlist,
|
||||
&flag, &enable, &physicsClientId))
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|iiOiidi", kwlist,
|
||||
&flag, &enable, &pyLightPosition, &shadowMapResolution, &shadowMapWorldSize, &remoteSyncTransformInterval, &physicsClientId))
|
||||
return NULL;
|
||||
|
||||
sm = getPhysicsClient(physicsClientId);
|
||||
@@ -5889,7 +5892,31 @@ static PyObject* pybullet_configureDebugVisualizer(PyObject* self, PyObject* arg
|
||||
|
||||
{
|
||||
b3SharedMemoryCommandHandle commandHandle = b3InitConfigureOpenGLVisualizer(sm);
|
||||
b3ConfigureOpenGLVisualizerSetVisualizationFlags(commandHandle, flag, enable);
|
||||
if (flag >= 0)
|
||||
{
|
||||
b3ConfigureOpenGLVisualizerSetVisualizationFlags(commandHandle, flag, enable);
|
||||
}
|
||||
if (pyLightPosition)
|
||||
{
|
||||
float lightPosition[3];
|
||||
if (pybullet_internalSetVector(pyLightPosition, lightPosition))
|
||||
{
|
||||
b3ConfigureOpenGLVisualizerSetLightPosition(commandHandle, lightPosition);
|
||||
}
|
||||
}
|
||||
if (shadowMapResolution > 0)
|
||||
{
|
||||
b3ConfigureOpenGLVisualizerSetShadowMapResolution(commandHandle, shadowMapResolution);
|
||||
}
|
||||
if (shadowMapWorldSize > 0)
|
||||
{
|
||||
b3ConfigureOpenGLVisualizerSetShadowMapWorldSize(commandHandle, shadowMapWorldSize);
|
||||
}
|
||||
if (remoteSyncTransformInterval >= 0)
|
||||
{
|
||||
b3ConfigureOpenGLVisualizerSetRemoteSyncTransformInterval(commandHandle, remoteSyncTransformInterval);
|
||||
}
|
||||
|
||||
b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
|
||||
}
|
||||
Py_INCREF(Py_None);
|
||||
|
||||
Reference in New Issue
Block a user