Merge pull request #988 from YunfeiBai/master
Log time stamp and set renderer in pybullet.
This commit is contained in:
@@ -578,6 +578,7 @@ struct GenericRobotStateLogger : public InternalStateLogger
|
|||||||
m_loggingType = STATE_LOGGING_GENERIC_ROBOT;
|
m_loggingType = STATE_LOGGING_GENERIC_ROBOT;
|
||||||
|
|
||||||
btAlignedObjectArray<std::string> structNames;
|
btAlignedObjectArray<std::string> structNames;
|
||||||
|
structNames.push_back("stepCount");
|
||||||
structNames.push_back("timeStamp");
|
structNames.push_back("timeStamp");
|
||||||
structNames.push_back("objectId");
|
structNames.push_back("objectId");
|
||||||
structNames.push_back("posX");
|
structNames.push_back("posX");
|
||||||
@@ -619,7 +620,7 @@ struct GenericRobotStateLogger : public InternalStateLogger
|
|||||||
structNames.push_back("u10");
|
structNames.push_back("u10");
|
||||||
structNames.push_back("u11");
|
structNames.push_back("u11");
|
||||||
|
|
||||||
m_structTypes = "fIfffffffffffffIffffffffffffffffffffffff";
|
m_structTypes = "IfIfffffffffffffIffffffffffffffffffffffff";
|
||||||
const char* fileNameC = fileName.c_str();
|
const char* fileNameC = fileName.c_str();
|
||||||
|
|
||||||
m_logFileHandle = createMinitaurLogFile(fileNameC, structNames, m_structTypes);
|
m_logFileHandle = createMinitaurLogFile(fileNameC, structNames, m_structTypes);
|
||||||
@@ -647,7 +648,10 @@ struct GenericRobotStateLogger : public InternalStateLogger
|
|||||||
}
|
}
|
||||||
|
|
||||||
MinitaurLogRecord logData;
|
MinitaurLogRecord logData;
|
||||||
logData.m_values.push_back(m_loggingTimeStamp);
|
int stepCount = m_loggingTimeStamp;
|
||||||
|
float timeStamp = m_loggingTimeStamp*m_dynamicsWorld->getSolverInfo().m_timeStep;
|
||||||
|
logData.m_values.push_back(stepCount);
|
||||||
|
logData.m_values.push_back(timeStamp);
|
||||||
|
|
||||||
btVector3 pos = mb->getBasePos();
|
btVector3 pos = mb->getBasePos();
|
||||||
btQuaternion ori = mb->getWorldToBaseRot().inverse();
|
btQuaternion ori = mb->getWorldToBaseRot().inverse();
|
||||||
|
|||||||
@@ -67,14 +67,14 @@ print('item num:'),
|
|||||||
print(itemNum)
|
print(itemNum)
|
||||||
|
|
||||||
for record in log:
|
for record in log:
|
||||||
Id = record[1]
|
Id = record[2]
|
||||||
pos = [record[2],record[3],record[4]]
|
pos = [record[3],record[4],record[5]]
|
||||||
orn = [record[5],record[6],record[7],record[8]]
|
orn = [record[6],record[7],record[8],record[9]]
|
||||||
p.resetBasePositionAndOrientation(Id,pos,orn)
|
p.resetBasePositionAndOrientation(Id,pos,orn)
|
||||||
numJoints = p.getNumJoints(Id)
|
numJoints = p.getNumJoints(Id)
|
||||||
for i in range (numJoints):
|
for i in range (numJoints):
|
||||||
jointInfo = p.getJointInfo(Id,i)
|
jointInfo = p.getJointInfo(Id,i)
|
||||||
qIndex = jointInfo[3]
|
qIndex = jointInfo[3]
|
||||||
if qIndex > -1:
|
if qIndex > -1:
|
||||||
p.resetJointState(Id,i,record[qIndex-7+16])
|
p.resetJointState(Id,i,record[qIndex-7+17])
|
||||||
sleep(0.0005)
|
sleep(0.0005)
|
||||||
@@ -3834,10 +3834,10 @@ static PyObject* pybullet_getContactPointData(PyObject* self, PyObject* args, Py
|
|||||||
|
|
||||||
|
|
||||||
/// Render an image from the current timestep of the simulation, width, height are required, other args are optional
|
/// Render an image from the current timestep of the simulation, width, height are required, other args are optional
|
||||||
// getCameraImage(w, h, view[16], projection[16], lightDir[3], lightColor[3], lightDist, hasShadow, lightAmbientCoeff, lightDiffuseCoeff, lightSpecularCoeff)
|
// getCameraImage(w, h, view[16], projection[16], lightDir[3], lightColor[3], lightDist, hasShadow, lightAmbientCoeff, lightDiffuseCoeff, lightSpecularCoeff, renderer)
|
||||||
static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObject *keywds)
|
static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObject *keywds)
|
||||||
{
|
{
|
||||||
/// request an image from a simulated camera, using a software renderer.
|
/// request an image from a simulated camera, using software or hardware renderer.
|
||||||
struct b3CameraImageData imageData;
|
struct b3CameraImageData imageData;
|
||||||
PyObject* objViewMat = 0, *objProjMat = 0, *lightDirObj = 0, *lightColorObj = 0;
|
PyObject* objViewMat = 0, *objProjMat = 0, *lightDirObj = 0, *lightColorObj = 0;
|
||||||
int width, height;
|
int width, height;
|
||||||
@@ -3850,14 +3850,15 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec
|
|||||||
float lightAmbientCoeff = 0.6;
|
float lightAmbientCoeff = 0.6;
|
||||||
float lightDiffuseCoeff = 0.35;
|
float lightDiffuseCoeff = 0.35;
|
||||||
float lightSpecularCoeff = 0.05;
|
float lightSpecularCoeff = 0.05;
|
||||||
|
int renderer = 0;
|
||||||
// inialize cmd
|
// inialize cmd
|
||||||
b3SharedMemoryCommandHandle command;
|
b3SharedMemoryCommandHandle command;
|
||||||
int physicsClientId = 0;
|
int physicsClientId = 0;
|
||||||
b3PhysicsClientHandle sm = 0;
|
b3PhysicsClientHandle sm = 0;
|
||||||
// set camera resolution, optionally view, projection matrix, light direction, light color, light distance, shadow
|
// set camera resolution, optionally view, projection matrix, light direction, light color, light distance, shadow
|
||||||
static char *kwlist[] = { "width", "height", "viewMatrix", "projectionMatrix", "lightDirection", "lightColor", "lightDistance", "shadow", "lightAmbientCoeff", "lightDiffuseCoeff", "lightSpecularCoeff", "physicsClientId", NULL };
|
static char *kwlist[] = { "width", "height", "viewMatrix", "projectionMatrix", "lightDirection", "lightColor", "lightDistance", "shadow", "lightAmbientCoeff", "lightDiffuseCoeff", "lightSpecularCoeff", "renderer", "physicsClientId", NULL };
|
||||||
|
|
||||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|OOOOfifffi", kwlist, &width, &height, &objViewMat, &objProjMat, &lightDirObj, &lightColorObj, &lightDist, &hasShadow, &lightAmbientCoeff, &lightDiffuseCoeff, &lightSpecularCoeff,&physicsClientId))
|
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|OOOOfifffii", kwlist, &width, &height, &objViewMat, &objProjMat, &lightDirObj, &lightColorObj, &lightDist, &hasShadow, &lightAmbientCoeff, &lightDiffuseCoeff, &lightSpecularCoeff, &renderer, &physicsClientId))
|
||||||
{
|
{
|
||||||
return NULL;
|
return NULL;
|
||||||
}
|
}
|
||||||
@@ -3895,6 +3896,8 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec
|
|||||||
b3RequestCameraImageSetLightDiffuseCoeff(command, lightDiffuseCoeff);
|
b3RequestCameraImageSetLightDiffuseCoeff(command, lightDiffuseCoeff);
|
||||||
b3RequestCameraImageSetLightSpecularCoeff(command, lightSpecularCoeff);
|
b3RequestCameraImageSetLightSpecularCoeff(command, lightSpecularCoeff);
|
||||||
|
|
||||||
|
b3RequestCameraImageSelectRenderer(command, renderer);
|
||||||
|
|
||||||
if (b3CanSubmitCommand(sm))
|
if (b3CanSubmitCommand(sm))
|
||||||
{
|
{
|
||||||
b3SharedMemoryStatusHandle statusHandle;
|
b3SharedMemoryStatusHandle statusHandle;
|
||||||
@@ -5104,7 +5107,7 @@ static PyMethodDef SpamMethods[] = {
|
|||||||
|
|
||||||
{ "getCameraImage",(PyCFunction)pybullet_getCameraImage, METH_VARARGS| METH_KEYWORDS,
|
{ "getCameraImage",(PyCFunction)pybullet_getCameraImage, METH_VARARGS| METH_KEYWORDS,
|
||||||
"Render an image (given the pixel resolution width, height, camera viewMatrix "
|
"Render an image (given the pixel resolution width, height, camera viewMatrix "
|
||||||
", projectionMatrix, lightDirection, lightColor, lightDistance, shadow, lightAmbientCoeff, lightDiffuseCoeff, and lightSpecularCoeff), and return the "
|
", projectionMatrix, lightDirection, lightColor, lightDistance, shadow, lightAmbientCoeff, lightDiffuseCoeff, lightSpecularCoeff, and renderer), and return the "
|
||||||
"8-8-8bit RGB pixel data and floating point depth values"
|
"8-8-8bit RGB pixel data and floating point depth values"
|
||||||
#ifdef PYBULLET_USE_NUMPY
|
#ifdef PYBULLET_USE_NUMPY
|
||||||
" as NumPy arrays"
|
" as NumPy arrays"
|
||||||
|
|||||||
Reference in New Issue
Block a user