mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-13 21:30:09 +00:00
Merge branch 'master' of https://github.com/erwincoumans/bullet3
This commit is contained in:
commit
e09dc74bd8
@ -113,6 +113,7 @@ SET(BulletRoboticsGUI_SRCS ${BulletRoboticsGUI_INCLUDES}
|
||||
../../examples/SharedMemory/GraphicsServerExample.cpp
|
||||
../../examples/SharedMemory/GraphicsClientExample.cpp
|
||||
../../examples/SharedMemory/RemoteGUIHelper.cpp
|
||||
../../examples/SharedMemory/RemoteGUIHelperTCP.cpp
|
||||
../../examples/SharedMemory/GraphicsServerExample.h
|
||||
../../examples/SharedMemory/GraphicsClientExample.h
|
||||
../../examples/SharedMemory/RemoteGUIHelper.h
|
||||
|
@ -18,6 +18,7 @@ RobotSimulatorMain.cpp
|
||||
../SharedMemory/GraphicsServerExample.cpp
|
||||
../SharedMemory/GraphicsClientExample.cpp
|
||||
../SharedMemory/RemoteGUIHelper.cpp
|
||||
../SharedMemory/RemoteGUIHelperTCP.cpp
|
||||
../SharedMemory/GraphicsServerExample.h
|
||||
../SharedMemory/GraphicsClientExample.h
|
||||
../SharedMemory/RemoteGUIHelper.h
|
||||
@ -32,6 +33,7 @@ RobotSimulatorMain.cpp
|
||||
|
||||
IF(BUILD_CLSOCKET)
|
||||
ADD_DEFINITIONS(-DBT_ENABLE_CLSOCKET)
|
||||
ADD_DEFINITIONS(${OSDEF})
|
||||
ENDIF(BUILD_CLSOCKET)
|
||||
|
||||
|
||||
|
@ -52,7 +52,7 @@ void submitStatus(CActiveSocket* pClient, GraphicsSharedMemoryStatus& serverStat
|
||||
|
||||
if (gVerboseNetworkMessagesServer)
|
||||
{
|
||||
//printf("buffer.size = %d\n", buffer.size());
|
||||
printf("buffer.size = %d\n", buffer.size());
|
||||
printf("serverStatus packed size = %d\n", sz);
|
||||
}
|
||||
|
||||
@ -63,7 +63,8 @@ void submitStatus(CActiveSocket* pClient, GraphicsSharedMemoryStatus& serverStat
|
||||
packetData[i + curPos] = statBytes[i];
|
||||
}
|
||||
curPos += sizeof(GraphicsSharedMemoryStatus);
|
||||
|
||||
if (gVerboseNetworkMessagesServer)
|
||||
printf("serverStatus.m_numDataStreamBytes=%d\n", serverStatus.m_numDataStreamBytes);
|
||||
for (int i = 0; i < serverStatus.m_numDataStreamBytes; i++)
|
||||
{
|
||||
packetData[i + curPos] = buffer[i];
|
||||
@ -199,6 +200,7 @@ void TCPThreadFunc(void* userPtr, void* lsMemory)
|
||||
|
||||
do
|
||||
{
|
||||
|
||||
{
|
||||
b3Clock::usleep(0);
|
||||
}
|
||||
@ -238,15 +240,18 @@ void TCPThreadFunc(void* userPtr, void* lsMemory)
|
||||
//----------------------------------------------------------------------
|
||||
// Receive request from the client.
|
||||
//----------------------------------------------------------------------
|
||||
|
||||
while (cachedSharedParam != eTCPRequestTerminate)
|
||||
{
|
||||
//printf("try receive\n");
|
||||
|
||||
bool receivedData = false;
|
||||
|
||||
int maxLen = 4 + sizeof(GraphicsSharedMemoryCommand) + GRAPHICS_SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE;
|
||||
|
||||
|
||||
|
||||
if (pClient->Receive(maxLen))
|
||||
{
|
||||
|
||||
//heuristic to detect disconnected clients
|
||||
CSimpleSocket::CSocketError err = pClient->GetSocketError();
|
||||
|
||||
@ -258,14 +263,16 @@ void TCPThreadFunc(void* userPtr, void* lsMemory)
|
||||
|
||||
if (curNumErr > 100)
|
||||
{
|
||||
printf("TCP Connection error = %d, curNumErr = %d\n", (int)err, curNumErr);
|
||||
break;
|
||||
///printf("TCP Connection error = %d, curNumErr = %d\n", (int)err, curNumErr);
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
curNumErr = 0;
|
||||
char* msg2 = (char*)pClient->GetData();
|
||||
int numBytesRec2 = pClient->GetBytesReceived();
|
||||
if (gVerboseNetworkMessagesServer)
|
||||
printf("numBytesRec2=%d\n", numBytesRec2);
|
||||
if (numBytesRec2 < 0)
|
||||
{
|
||||
numBytesRec2 = 0;
|
||||
@ -377,7 +384,7 @@ void TCPThreadFunc(void* userPtr, void* lsMemory)
|
||||
if (err != CSimpleSocket::SocketSuccess || !pClient->IsSocketValid())
|
||||
{
|
||||
curNumErr++;
|
||||
printf("TCP Connection error = %d, curNumErr = %d\n", (int)err, curNumErr);
|
||||
//printf("TCP Connection error = %d, curNumErr = %d\n", (int)err, curNumErr);
|
||||
}
|
||||
char* msg2 = (char*)pClient->GetData();
|
||||
int numBytesRec2 = pClient->GetBytesReceived();
|
||||
@ -535,7 +542,7 @@ void TCPThreadFunc(void* userPtr, void* lsMemory)
|
||||
{
|
||||
submitStatus(pClient, args->m_serverStatus, buffer);
|
||||
}
|
||||
|
||||
|
||||
bytesReceived.clear();
|
||||
}
|
||||
else
|
||||
@ -566,9 +573,10 @@ void TCPThreadFunc(void* userPtr, void* lsMemory)
|
||||
args->m_cs->unlock();
|
||||
|
||||
} while (cachedSharedParam != eTCPRequestTerminate);
|
||||
|
||||
#ifdef BT_ENABLE_CLSOCKET
|
||||
socket.Close();
|
||||
socket.Shutdown(CSimpleSocket::Both);
|
||||
#endif
|
||||
}
|
||||
else
|
||||
{
|
||||
|
@ -129,7 +129,7 @@ struct RemoteGUIHelperTCPInternalData
|
||||
|
||||
int rBytes = m_tcpSocket.Receive(maxLen);
|
||||
if (rBytes <= 0)
|
||||
return false;
|
||||
return 0;
|
||||
|
||||
//append to tmp buffer
|
||||
//recBytes
|
||||
@ -196,12 +196,13 @@ struct RemoteGUIHelperTCPInternalData
|
||||
return true;
|
||||
|
||||
m_tcpSocket.Initialize();
|
||||
|
||||
|
||||
m_isConnected = m_tcpSocket.Open(m_hostName.c_str(), m_port);
|
||||
if (m_isConnected)
|
||||
{
|
||||
m_tcpSocket.SetSendTimeout(m_timeOutInSeconds, 0);
|
||||
m_tcpSocket.SetReceiveTimeout(m_timeOutInSeconds, 0);
|
||||
|
||||
}
|
||||
int key = GRAPHICS_SHARED_MEMORY_MAGIC_NUMBER;
|
||||
m_tcpSocket.Send((uint8*)&key, 4);
|
||||
|
@ -314,7 +314,9 @@ B3_SHARED_API b3PhysicsClientHandle b3CreateInProcessPhysicsServerFromExistingEx
|
||||
return (b3PhysicsClientHandle)cl;
|
||||
}
|
||||
|
||||
#include "RemoteGuiHelperTCP.h"
|
||||
#ifdef BT_ENABLE_CLSOCKET
|
||||
|
||||
#include "RemoteGUIHelperTCP.h"
|
||||
|
||||
B3_SHARED_API b3PhysicsClientHandle b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnectTCP(const char* hostName, int port)
|
||||
{
|
||||
@ -566,4 +568,4 @@ B3_SHARED_API b3PhysicsClientHandle b3CreateInProcessGraphicsServerAndConnectMai
|
||||
return (b3PhysicsClientHandle)cl;
|
||||
}
|
||||
|
||||
|
||||
#endif
|
||||
|
2
setup.py
2
setup.py
@ -129,7 +129,7 @@ sources = ["examples/pybullet/pybullet.c"]\
|
||||
+["examples/SharedMemory/GraphicsClientExample.cpp"]\
|
||||
+["examples/SharedMemory/GraphicsServerExample.cpp"]\
|
||||
+["examples/SharedMemory/RemoteGUIHelper.cpp"]\
|
||||
+["examples/SharedMemory/RemoteGuiHelperTCP.cpp"]\
|
||||
+["examples/SharedMemory/RemoteGUIHelperTCP.cpp"]\
|
||||
+["examples/SharedMemory/PhysicsServerExample.cpp"]\
|
||||
+["examples/SharedMemory/PhysicsServerExampleBullet2.cpp"]\
|
||||
+["examples/SharedMemory/SharedMemoryInProcessPhysicsC_API.cpp"]\
|
||||
|
Loading…
Reference in New Issue
Block a user