mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-13 05:10:08 +00:00
Merge pull request #3208 from erwincoumans/master
allow to specify hostName
This commit is contained in:
commit
d274093f76
@ -123,6 +123,7 @@ struct GUIHelperInterface
|
||||
virtual void dumpFramesToVideo(const char* mp4FileName){};
|
||||
virtual void drawDebugDrawerLines(){}
|
||||
virtual void clearLines(){}
|
||||
virtual bool isRemoteVisualizer() { return false; }
|
||||
};
|
||||
|
||||
///the DummyGUIHelper does nothing, so we can test the examples without GUI/graphics (in 'console mode')
|
||||
|
@ -2156,8 +2156,8 @@ void PhysicsServerExample::updateGraphics()
|
||||
|
||||
m_multiThreadedHelper->m_childGuiHelper->setVisualizerFlag(m_multiThreadedHelper->m_visualizerFlag, m_multiThreadedHelper->m_visualizerEnable);
|
||||
|
||||
//postpone the release until an actual frame is rendered
|
||||
if (flag == COV_ENABLE_SINGLE_STEP_RENDERING)
|
||||
//postpone the release until an actual frame is rendered, unless it is a remote visualizer
|
||||
if ((!m_multiThreadedHelper->m_childGuiHelper->isRemoteVisualizer()) && flag == COV_ENABLE_SINGLE_STEP_RENDERING)
|
||||
{
|
||||
m_multiThreadedHelper->getCriticalSection()->setSharedParam(1, eGUIHelperSetVisualizerFlagCheckRenderedFrame);
|
||||
}
|
||||
|
@ -70,6 +70,7 @@ struct RemoteGUIHelperTCP : public GUIHelperInterface
|
||||
virtual void removeAllUserDebugItems();
|
||||
|
||||
int uploadData(const unsigned char* data, int sizeInBytes, int slot);
|
||||
virtual bool isRemoteVisualizer() { return true; }
|
||||
};
|
||||
|
||||
#endif //REMOTE_HELPER_TCP_H
|
||||
|
@ -10,7 +10,12 @@ clid = p.connect(p.SHARED_MEMORY)
|
||||
|
||||
if (clid < 0):
|
||||
p.connect(p.GUI)
|
||||
|
||||
p.setPhysicsEngineParameter(enableConeFriction=0)
|
||||
|
||||
p.setAdditionalSearchPath(pybullet_data.getDataPath())
|
||||
|
||||
|
||||
p.loadURDF("plane.urdf", [0, 0, -0.3])
|
||||
husky = p.loadURDF("husky/husky.urdf", [0.290388, 0.329902, -0.310270],
|
||||
[0.002328, -0.000984, 0.996491, 0.083659])
|
||||
@ -62,7 +67,7 @@ useNullSpace = 0
|
||||
useOrientation = 0
|
||||
#If we set useSimulation=0, it sets the arm pose to be the IK result directly without using dynamic control.
|
||||
#This can be used to test the IK result accuracy.
|
||||
useSimulation = 0
|
||||
useSimulation = 1
|
||||
useRealTimeSimulation = 1
|
||||
p.setRealTimeSimulation(useRealTimeSimulation)
|
||||
#trailDuration is duration (in seconds) after debug lines will be removed automatically
|
||||
|
@ -9,7 +9,7 @@ import pybullet
|
||||
class BulletClient(object):
|
||||
"""A wrapper for pybullet to manage different clients."""
|
||||
|
||||
def __init__(self, connection_mode=None):
|
||||
def __init__(self, connection_mode=None, hostName=None):
|
||||
"""Creates a Bullet client and connects to a simulation.
|
||||
|
||||
Args:
|
||||
@ -27,7 +27,10 @@ class BulletClient(object):
|
||||
return
|
||||
else:
|
||||
connection_mode = pybullet.DIRECT
|
||||
self._client = pybullet.connect(connection_mode)
|
||||
if hostName is None:
|
||||
self._client = pybullet.connect(connection_mode)
|
||||
else:
|
||||
self._client = pybullet.connect(connection_mode, hostName=hostName)
|
||||
|
||||
def __del__(self):
|
||||
"""Clean up connection if not already done."""
|
||||
|
@ -403,6 +403,7 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P
|
||||
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|is", kwlist1, &method, &key, &options))
|
||||
{
|
||||
PyErr_Clear();
|
||||
int port = -1;
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|sis", kwlist2, &method, &hostName, &port, &options))
|
||||
{
|
||||
@ -11641,6 +11642,8 @@ static PyObject* pybullet_calculateInverseKinematics2(PyObject* self,
|
||||
free(upperLimits);
|
||||
free(jointRanges);
|
||||
free(restPoses);
|
||||
free(positions);
|
||||
free(indices);
|
||||
return NULL;
|
||||
}
|
||||
else
|
||||
@ -11761,12 +11764,16 @@ static PyObject* pybullet_calculateInverseKinematics2(PyObject* self,
|
||||
}
|
||||
|
||||
free(ikOutPutJointPos);
|
||||
free(positions);
|
||||
free(indices);
|
||||
return pylist;
|
||||
}
|
||||
else
|
||||
{
|
||||
PyErr_SetString(SpamError,
|
||||
"Error in calculateInverseKinematics");
|
||||
free(positions);
|
||||
free(indices);
|
||||
return NULL;
|
||||
}
|
||||
}
|
||||
@ -11774,8 +11781,13 @@ static PyObject* pybullet_calculateInverseKinematics2(PyObject* self,
|
||||
{
|
||||
PyErr_SetString(SpamError,
|
||||
"calculateInverseKinematics couldn't extract position vector3");
|
||||
free(positions);
|
||||
free(indices);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
free(positions);
|
||||
free(indices);
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user