export TCP connection mode to pybullet
made TCP disconnection detection more reliable
This commit is contained in:
@@ -74,8 +74,10 @@ int main(int argc, char *argv[])
|
||||
socket.Initialize();
|
||||
|
||||
socket.Listen("localhost", port);
|
||||
|
||||
b3AlignedObjectArray<char> bytesReceived;
|
||||
socket.SetBlocking();
|
||||
|
||||
int curNumErr = 0;
|
||||
|
||||
|
||||
while (!exitRequested)
|
||||
{
|
||||
@@ -83,9 +85,12 @@ int main(int argc, char *argv[])
|
||||
|
||||
if ((pClient = socket.Accept()) != NULL)
|
||||
{
|
||||
b3AlignedObjectArray<char> bytesReceived;
|
||||
|
||||
int clientPort = socket.GetClientPort();
|
||||
printf("connected from %s:%d\n", socket.GetClientAddr(),clientPort);
|
||||
|
||||
|
||||
//----------------------------------------------------------------------
|
||||
// Receive request from the client.
|
||||
//----------------------------------------------------------------------
|
||||
@@ -96,9 +101,27 @@ int main(int argc, char *argv[])
|
||||
|
||||
int maxLen = 4 + sizeof(SharedMemoryStatus)+SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE;
|
||||
|
||||
|
||||
//heuristic to detect disconnected clients
|
||||
CSimpleSocket::CSocketError err = pClient->GetSocketError();
|
||||
if (err != CSimpleSocket::SocketSuccess)
|
||||
{
|
||||
b3Clock::usleep(100);
|
||||
|
||||
curNumErr++;
|
||||
|
||||
if (curNumErr>100)
|
||||
{
|
||||
printf("TCP Connection error = %d, curNumErr = %d\n", (int)err, curNumErr);
|
||||
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
if (pClient->Receive(maxLen))
|
||||
{
|
||||
|
||||
|
||||
curNumErr = 0;
|
||||
char* msg2 = (char*) pClient->GetData();
|
||||
int numBytesRec2 = pClient->GetBytesReceived();
|
||||
|
||||
@@ -221,9 +244,8 @@ int main(int argc, char *argv[])
|
||||
}
|
||||
if (!receivedData)
|
||||
{
|
||||
printf("Didn't receive data.\n");
|
||||
break;
|
||||
}
|
||||
//printf("Didn't receive data.\n");
|
||||
}
|
||||
}
|
||||
printf("Disconnecting client.\n");
|
||||
pClient->Close();
|
||||
|
||||
@@ -413,6 +413,14 @@ public:
|
||||
CSocketError GetSocketError(void) {
|
||||
return m_socketErrno;
|
||||
};
|
||||
/*
|
||||
CSocketError GetSocketError(void) {
|
||||
CSocketError err = m_socketErrno;
|
||||
m_socketErrno = SocketSuccess;
|
||||
return err;
|
||||
|
||||
};
|
||||
*/
|
||||
|
||||
/// Get the total time the of the last operation in milliseconds.
|
||||
/// @return number of milliseconds of last operation.
|
||||
|
||||
@@ -95,7 +95,7 @@ ENDIF(WIN32)
|
||||
|
||||
|
||||
IF(BUILD_PYBULLET_ENET)
|
||||
ADD_LIBRARY(pybullet SHARED ${pybullet_SRCS}
|
||||
set(pybullet_SRCS ${pybullet_SRCS}
|
||||
../../examples/SharedMemory/PhysicsClientUDP.cpp
|
||||
../../examples/SharedMemory/PhysicsClientUDP_C_API.cpp
|
||||
../../examples/SharedMemory/PhysicsClientUDP.h
|
||||
@@ -110,10 +110,11 @@ IF(BUILD_PYBULLET_ENET)
|
||||
../../examples/ThirdPartyLibs/enet/peer.c
|
||||
../../examples/ThirdPartyLibs/enet/protocol.c
|
||||
)
|
||||
ELSE(BUILD_PYBULLET_ENET)
|
||||
ADD_LIBRARY(pybullet SHARED ${pybullet_SRCS})
|
||||
ENDIF(BUILD_PYBULLET_ENET)
|
||||
|
||||
|
||||
ADD_LIBRARY(pybullet SHARED ${pybullet_SRCS})
|
||||
|
||||
SET_TARGET_PROPERTIES(pybullet PROPERTIES PREFIX "")
|
||||
SET_TARGET_PROPERTIES(pybullet PROPERTIES POSTFIX "")
|
||||
|
||||
|
||||
@@ -5,6 +5,10 @@
|
||||
#include "../SharedMemory/PhysicsClientUDP_C_API.h"
|
||||
#endif //BT_ENABLE_ENET
|
||||
|
||||
#ifdef BT_ENABLE_CLSOCKET
|
||||
#include "../SharedMemory/PhysicsClientTCP_C_API.h"
|
||||
#endif //BT_ENABLE_CLSOCKET
|
||||
|
||||
#ifdef __APPLE__
|
||||
#include <Python/Python.h>
|
||||
#else
|
||||
@@ -25,6 +29,7 @@ enum eCONNECT_METHOD {
|
||||
eCONNECT_DIRECT = 2,
|
||||
eCONNECT_SHARED_MEMORY = 3,
|
||||
eCONNECT_UDP = 4,
|
||||
eCONNECT_TCP = 5,
|
||||
};
|
||||
|
||||
static PyObject* SpamError;
|
||||
@@ -227,7 +232,9 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P
|
||||
{
|
||||
|
||||
int key = SHARED_MEMORY_KEY;
|
||||
int port = 1234;
|
||||
int udpPort = 1234;
|
||||
int tcpPort = 6667;
|
||||
|
||||
const char* hostName = "localhost";
|
||||
|
||||
int size = PySequence_Size(args);
|
||||
@@ -236,7 +243,7 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P
|
||||
if (!PyArg_ParseTuple(args, "i", &method)) {
|
||||
PyErr_SetString(SpamError,
|
||||
"connectPhysicsServer expected argument GUI, "
|
||||
"DIRECT, SHARED_MEMORY or UDP");
|
||||
"DIRECT, SHARED_MEMORY, UDP or TCP");
|
||||
return NULL;
|
||||
}
|
||||
}
|
||||
@@ -250,7 +257,7 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P
|
||||
if (sPhysicsClientsGUI[i] ==eCONNECT_GUI)
|
||||
{
|
||||
PyErr_SetString(SpamError,
|
||||
"Only one local in-process GUI connection allowed. Use DIRECT connection mode or start a separate GUI physics server (ExampleBrowser, App_SharedMemoryPhysics_GUI, App_SharedMemoryPhysics_VR) and connect over SHARED_MEMORY or UDP instead.");
|
||||
"Only one local in-process GUI connection allowed. Use DIRECT connection mode or start a separate GUI physics server (ExampleBrowser, App_SharedMemoryPhysics_GUI, App_SharedMemoryPhysics_VR) and connect over SHARED_MEMORY, UDP or TCP instead.");
|
||||
return NULL;
|
||||
}
|
||||
}
|
||||
@@ -275,12 +282,18 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P
|
||||
|
||||
if (size == 3)
|
||||
{
|
||||
int port = -1;
|
||||
if (!PyArg_ParseTuple(args, "isi", &method, &hostName, &port))
|
||||
{
|
||||
PyErr_SetString(SpamError,
|
||||
"connectPhysicsServer 3 arguments: method, hostname, port");
|
||||
return NULL;
|
||||
}
|
||||
if (port>=0)
|
||||
{
|
||||
udpPort = port;
|
||||
tcpPort = port;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -308,7 +321,7 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P
|
||||
{
|
||||
#ifdef BT_ENABLE_ENET
|
||||
|
||||
sm = b3ConnectPhysicsUDP(hostName, port);
|
||||
sm = b3ConnectPhysicsUDP(hostName, udpPort);
|
||||
#else
|
||||
PyErr_SetString(SpamError, "UDP is not enabled in this pybullet build");
|
||||
return NULL;
|
||||
@@ -316,6 +329,20 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P
|
||||
|
||||
break;
|
||||
}
|
||||
case eCONNECT_TCP:
|
||||
{
|
||||
#ifdef BT_ENABLE_CLSOCKET
|
||||
|
||||
sm = b3ConnectPhysicsTCP(hostName, tcpPort);
|
||||
#else
|
||||
PyErr_SetString(SpamError, "TCP is not enabled in this pybullet build");
|
||||
return NULL;
|
||||
#endif //BT_ENABLE_CLSOCKET
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
|
||||
|
||||
default: {
|
||||
PyErr_SetString(SpamError, "connectPhysicsServer unexpected argument");
|
||||
@@ -5126,6 +5153,7 @@ initpybullet(void)
|
||||
PyModule_AddIntConstant(m, "DIRECT", eCONNECT_DIRECT); // user read
|
||||
PyModule_AddIntConstant(m, "GUI", eCONNECT_GUI); // user read
|
||||
PyModule_AddIntConstant(m, "UDP", eCONNECT_UDP); // user read
|
||||
PyModule_AddIntConstant(m, "TCP", eCONNECT_TCP); // user read
|
||||
|
||||
PyModule_AddIntConstant(m, "JOINT_REVOLUTE", eRevoluteType); // user read
|
||||
PyModule_AddIntConstant(m, "JOINT_PRISMATIC", ePrismaticType); // user read
|
||||
|
||||
Reference in New Issue
Block a user