Merge pull request #1886 from erwincoumans/master
pybullet, fix single step synchronous rendering, add missing files in pip version 2.1.8
This commit is contained in:
@@ -7,11 +7,6 @@ recursive-include src *.h
|
||||
recursive-include src *.hpp
|
||||
recursive-include examples/pybullet/gym *.*
|
||||
include examples/ThirdPartyLibs/enet/unix.c
|
||||
include examples/OpenGLWindow/X11OpenGLWindow.cpp
|
||||
include examples/OpenGLWindow/*.cpp
|
||||
recursive-include examples/ThirdPartyLibs/glad *.*
|
||||
include examples/ThirdPartyLibs/enet/win32.c
|
||||
include examples/OpenGLWindow/Win32Window.cpp
|
||||
include examples/OpenGLWindow/Win32OpenGLWindow.cpp
|
||||
include examples/ThirdPartyLibs/Glew/glew.c
|
||||
include examples/OpenGLWindow/MacOpenGLWindow.cpp
|
||||
include examples/OpenGLWindow/MacOpenGLWindowObjC.m
|
||||
|
||||
@@ -393,7 +393,15 @@ void OpenGLExampleBrowserVisualizerFlagCallback(int flag, bool enable)
|
||||
|
||||
if (flag == COV_ENABLE_SINGLE_STEP_RENDERING)
|
||||
{
|
||||
singleStepSimulation = true;
|
||||
if (enable)
|
||||
{
|
||||
gEnableRenderLoop = false;
|
||||
singleStepSimulation = true;
|
||||
} else
|
||||
{
|
||||
gEnableRenderLoop = true;
|
||||
singleStepSimulation = false;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -1235,7 +1243,7 @@ void OpenGLExampleBrowser::update(float deltaTime)
|
||||
{
|
||||
b3ChromeUtilsEnableProfiling();
|
||||
|
||||
if (!gEnableRenderLoop)
|
||||
if (!gEnableRenderLoop && !singleStepSimulation)
|
||||
{
|
||||
sCurrentDemo->updateGraphics();
|
||||
return;
|
||||
|
||||
@@ -67,7 +67,11 @@ struct GRPCNetworkedInternalData
|
||||
{
|
||||
if (m_isConnected)
|
||||
return true;
|
||||
std::string hostport = m_hostName + ':' + std::to_string(m_port);
|
||||
std::string hostport = m_hostName;
|
||||
if (m_port >= 0)
|
||||
{
|
||||
hostport += ':' + std::to_string(m_port);
|
||||
}
|
||||
m_grpcChannel = grpc::CreateChannel(
|
||||
hostport, grpc::InsecureChannelCredentials());
|
||||
|
||||
|
||||
@@ -137,6 +137,7 @@ enum MultiThreadedGUIHelperCommunicationEnums
|
||||
eGUIHelperGetShapeIndexFromInstance,
|
||||
eGUIHelperChangeTexture,
|
||||
eGUIHelperRemoveTexture,
|
||||
eGUIHelperSetVisualizerFlagCheckRenderedFrame,
|
||||
};
|
||||
|
||||
|
||||
@@ -940,7 +941,9 @@ public:
|
||||
|
||||
int m_visualizerFlag;
|
||||
int m_visualizerEnable;
|
||||
void setVisualizerFlag(int flag, int enable)
|
||||
int m_renderedFrames;
|
||||
|
||||
void setVisualizerFlag(int flag, int enable)
|
||||
{
|
||||
m_visualizerFlag = flag;
|
||||
m_visualizerEnable = enable;
|
||||
@@ -1358,6 +1361,7 @@ class PhysicsServerExample : public SharedMemoryCommon
|
||||
int m_canvasRGBIndex;
|
||||
int m_canvasDepthIndex;
|
||||
int m_canvasSegMaskIndex;
|
||||
|
||||
|
||||
// int m_options;
|
||||
|
||||
@@ -1365,6 +1369,8 @@ class PhysicsServerExample : public SharedMemoryCommon
|
||||
TinyVRGui* m_tinyVrGui;
|
||||
#endif
|
||||
|
||||
int m_renderedFrames;
|
||||
|
||||
public:
|
||||
|
||||
PhysicsServerExample(MultiThreadedOpenGLGuiHelper* helper, CommandProcessorCreationInterface* commandProcessorCreator, SharedMemoryInterface* sharedMem=0, int options=0);
|
||||
@@ -1723,6 +1729,7 @@ m_canvasSegMaskIndex(-1)
|
||||
#ifdef BT_ENABLE_VR
|
||||
,m_tinyVrGui(0)
|
||||
#endif
|
||||
,m_renderedFrames(0)
|
||||
{
|
||||
|
||||
m_multiThreadedHelper = helper;
|
||||
@@ -2066,11 +2073,29 @@ void PhysicsServerExample::updateGraphics()
|
||||
gEnableDefaultMousePicking = (enable!=0);
|
||||
}
|
||||
|
||||
m_multiThreadedHelper->m_renderedFrames = m_renderedFrames;
|
||||
|
||||
m_multiThreadedHelper->m_childGuiHelper->setVisualizerFlag(m_multiThreadedHelper->m_visualizerFlag,m_multiThreadedHelper->m_visualizerEnable);
|
||||
m_multiThreadedHelper->mainThreadRelease();
|
||||
|
||||
//postpone the release until an actual frame is rendered
|
||||
if (flag == COV_ENABLE_SINGLE_STEP_RENDERING)
|
||||
{
|
||||
m_multiThreadedHelper->getCriticalSection()->setSharedParam(1,eGUIHelperSetVisualizerFlagCheckRenderedFrame);
|
||||
} else
|
||||
{
|
||||
m_multiThreadedHelper->mainThreadRelease();
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
|
||||
case eGUIHelperSetVisualizerFlagCheckRenderedFrame:
|
||||
{
|
||||
if (m_renderedFrames!=m_multiThreadedHelper->m_renderedFrames)
|
||||
{
|
||||
m_multiThreadedHelper->mainThreadRelease();
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
case eGUIHelperRegisterGraphicsInstance:
|
||||
{
|
||||
@@ -2732,6 +2757,8 @@ void PhysicsServerExample::drawUserDebugLines()
|
||||
|
||||
void PhysicsServerExample::renderScene()
|
||||
{
|
||||
m_renderedFrames++;
|
||||
|
||||
btTransform vrTrans;
|
||||
|
||||
|
||||
@@ -2893,12 +2920,14 @@ void PhysicsServerExample::renderScene()
|
||||
|
||||
drawUserDebugLines();
|
||||
|
||||
|
||||
|
||||
//m_args[0].m_cs->unlock();
|
||||
}
|
||||
|
||||
void PhysicsServerExample::physicsDebugDraw(int debugDrawFlags)
|
||||
{
|
||||
m_renderedFrames++;
|
||||
|
||||
if (gEnableSyncPhysicsRendering)
|
||||
{
|
||||
m_physicsServer.syncPhysicsToGraphics();
|
||||
|
||||
@@ -255,7 +255,11 @@ int main(int argc, char** argv)
|
||||
int port = 6667;
|
||||
parseArgs.GetCmdLineArgument("port", port);
|
||||
std::string hostName = "localhost";
|
||||
std::string hostNamePort = hostName + ":" + std::to_string(port);
|
||||
std::string hostNamePort = hostName;
|
||||
if (port>=0)
|
||||
{
|
||||
hostNamePort += ":" + std::to_string(port);
|
||||
}
|
||||
|
||||
gVerboseNetworkMessagesServer = parseArgs.CheckCmdLineFlag("verbose");
|
||||
|
||||
|
||||
File diff suppressed because one or more lines are too long
19
examples/pybullet/examples/grpcClient.py
Normal file
19
examples/pybullet/examples/grpcClient.py
Normal file
@@ -0,0 +1,19 @@
|
||||
|
||||
import pybullet as p
|
||||
|
||||
usePort = True
|
||||
|
||||
if (usePort):
|
||||
id = p.connect(p.GRPC,"localhost:12345")
|
||||
else:
|
||||
id = p.connect(p.GRPC,"localhost")
|
||||
print("id=",id)
|
||||
|
||||
if (id<0):
|
||||
print("Cannot connect to GRPC server")
|
||||
exit(0)
|
||||
|
||||
print ("Connected to GRPC")
|
||||
r2d2 = p.loadURDF("r2d2.urdf")
|
||||
print("numJoints = ", p.getNumJoints(r2d2))
|
||||
|
||||
29
examples/pybullet/examples/grpcServer.py
Normal file
29
examples/pybullet/examples/grpcServer.py
Normal file
@@ -0,0 +1,29 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
|
||||
useDirect = False
|
||||
usePort = True
|
||||
|
||||
p.connect(p.GUI)
|
||||
id = p.loadPlugin("grpcPlugin")
|
||||
#dynamically loading the plugin
|
||||
#id = p.loadPlugin("E:/develop/bullet3/bin/pybullet_grpcPlugin_vs2010_x64_debug.dll", postFix="_grpcPlugin")
|
||||
|
||||
#start the GRPC server at hostname, port
|
||||
if (id<0):
|
||||
print("Cannot load grpcPlugin")
|
||||
exit(0)
|
||||
|
||||
if usePort:
|
||||
p.executePluginCommand(id, "localhost:12345")
|
||||
else:
|
||||
p.executePluginCommand(id, "localhost")
|
||||
|
||||
while p.isConnected():
|
||||
if (useDirect):
|
||||
#Only in DIRECT mode, since there is no 'ping' you need to manually call to handle RCPs:
|
||||
numRPC = 10
|
||||
p.executePluginCommand(id, intArgs=[numRPC])
|
||||
else:
|
||||
dt = 1./240.
|
||||
time.sleep(dt)
|
||||
@@ -330,6 +330,7 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P
|
||||
int key = SHARED_MEMORY_KEY;
|
||||
int udpPort = 1234;
|
||||
int tcpPort = 6667;
|
||||
int grpcPort = -1;
|
||||
int argc = 0;
|
||||
char** argv=0;
|
||||
|
||||
@@ -352,6 +353,7 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P
|
||||
{
|
||||
udpPort = port;
|
||||
tcpPort = port;
|
||||
grpcPort = port;
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -437,7 +439,7 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P
|
||||
case eCONNECT_GRPC:
|
||||
{
|
||||
#ifdef BT_ENABLE_GRPC
|
||||
sm = b3ConnectPhysicsGRPC(hostName, tcpPort);
|
||||
sm = b3ConnectPhysicsGRPC(hostName, grpcPort);
|
||||
#else
|
||||
PyErr_SetString(SpamError, "GRPC is not enabled in this pybullet build");
|
||||
#endif
|
||||
|
||||
2
setup.py
2
setup.py
@@ -545,7 +545,7 @@ eglRender = Extension("eglRenderer",
|
||||
|
||||
setup(
|
||||
name = 'pybullet',
|
||||
version='2.1.6',
|
||||
version='2.1.9',
|
||||
description='Official Python Interface for the Bullet Physics SDK specialized for Robotics Simulation and Reinforcement Learning',
|
||||
long_description='pybullet is an easy to use Python module for physics simulation, robotics and deep reinforcement learning based on the Bullet Physics SDK. With pybullet you can load articulated bodies from URDF, SDF and other file formats. pybullet provides forward dynamics simulation, inverse dynamics computation, forward and inverse kinematics and collision detection and ray intersection queries. Aside from physics simulation, pybullet supports to rendering, with a CPU renderer and OpenGL visualization and support for virtual reality headsets.',
|
||||
url='https://github.com/bulletphysics/bullet3',
|
||||
|
||||
Reference in New Issue
Block a user