Get debug visualizer camera yaw, pitch, dist, and target.

This commit is contained in:
yunfeibai
2017-06-02 18:24:51 -07:00
parent e2a9fc33dc
commit 0a29c8d9af
8 changed files with 41 additions and 8 deletions

View File

@@ -57,7 +57,7 @@ struct GUIHelperInterface
virtual void resetCamera(float camDist, float yaw, float pitch, float camPosX,float camPosY, float camPosZ)=0; virtual void resetCamera(float camDist, float yaw, float pitch, float camPosX,float camPosY, float camPosZ)=0;
virtual bool getCameraInfo(int* width, int* height, float viewMatrix[16], float projectionMatrix[16], float camUp[3], float camForward[3],float hor[3], float vert[3] ) const virtual bool getCameraInfo(int* width, int* height, float viewMatrix[16], float projectionMatrix[16], float camUp[3], float camForward[3],float hor[3], float vert[3], float* yaw, float* pitch, float* camDist, float camTarget[3]) const
{ {
return false; return false;
} }

View File

@@ -984,7 +984,7 @@ void OpenGLGuiHelper::resetCamera(float camDist, float yaw, float pitch, float c
} }
} }
bool OpenGLGuiHelper::getCameraInfo(int* width, int* height, float viewMatrix[16], float projectionMatrix[16], float camUp[3], float camForward[3],float hor[3], float vert[3] ) const bool OpenGLGuiHelper::getCameraInfo(int* width, int* height, float viewMatrix[16], float projectionMatrix[16], float camUp[3], float camForward[3],float hor[3], float vert[3], float* yaw, float* pitch, float* camDist, float cameraTarget[3]) const
{ {
if (getRenderInterface() && getRenderInterface()->getActiveCamera()) if (getRenderInterface() && getRenderInterface()->getActiveCamera())
{ {
@@ -1030,6 +1030,13 @@ bool OpenGLGuiHelper::getCameraInfo(int* width, int* height, float viewMatrix[16
vert[0] = vertical[0]; vert[0] = vertical[0];
vert[1] = vertical[1]; vert[1] = vertical[1];
vert[2] = vertical[2]; vert[2] = vertical[2];
*yaw = getRenderInterface()->getActiveCamera()->getCameraYaw();
*pitch = getRenderInterface()->getActiveCamera()->getCameraPitch();
*camDist = getRenderInterface()->getActiveCamera()->getCameraDistance();
cameraTarget[0] = camTarget[0];
cameraTarget[1] = camTarget[1];
cameraTarget[2] = camTarget[2];
return true; return true;
} }
return false; return false;

View File

@@ -47,7 +47,7 @@ struct OpenGLGuiHelper : public GUIHelperInterface
virtual void resetCamera(float camDist, float yaw, float pitch, float camPosX,float camPosY, float camPosZ); virtual void resetCamera(float camDist, float yaw, float pitch, float camPosX,float camPosY, float camPosZ);
virtual bool getCameraInfo(int* width, int* height, float viewMatrix[16], float projectionMatrix[16], float camUp[3], float camForward[3],float hor[3], float vert[3] ) const; virtual bool getCameraInfo(int* width, int* height, float viewMatrix[16], float projectionMatrix[16], float camUp[3], float camForward[3],float hor[3], float vert[3], float* yaw, float* pitch, float* camDist, float camTarget[3]) const;
virtual void copyCameraImageData(const float viewMatrix[16], const float projectionMatrix[16], virtual void copyCameraImageData(const float viewMatrix[16], const float projectionMatrix[16],
unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels,

View File

@@ -271,7 +271,6 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId)
case CMD_REQUEST_CAMERA_IMAGE_DATA: case CMD_REQUEST_CAMERA_IMAGE_DATA:
{ {
///request an image from a simulated camera, using a software renderer. ///request an image from a simulated camera, using a software renderer.
b3SharedMemoryCommandHandle commandHandle = b3InitRequestCameraImage(m_physicsClientHandle); b3SharedMemoryCommandHandle commandHandle = b3InitRequestCameraImage(m_physicsClientHandle);
//b3RequestCameraImageSelectRenderer(commandHandle,ER_BULLET_HARDWARE_OPENGL); //b3RequestCameraImageSelectRenderer(commandHandle,ER_BULLET_HARDWARE_OPENGL);
@@ -328,6 +327,7 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId)
//b3Printf("Joint %d: %f", i, sensorState.m_jointMotorTorque); //b3Printf("Joint %d: %f", i, sensorState.m_jointMotorTorque);
} }
} }
break; break;
}; };

View File

@@ -4496,7 +4496,11 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
serverCmd.m_visualizerCameraResultArgs.m_camUp, serverCmd.m_visualizerCameraResultArgs.m_camUp,
serverCmd.m_visualizerCameraResultArgs.m_camForward, serverCmd.m_visualizerCameraResultArgs.m_camForward,
serverCmd.m_visualizerCameraResultArgs.m_horizontal, serverCmd.m_visualizerCameraResultArgs.m_horizontal,
serverCmd.m_visualizerCameraResultArgs.m_vertical); serverCmd.m_visualizerCameraResultArgs.m_vertical,
&serverCmd.m_visualizerCameraResultArgs.m_yaw,
&serverCmd.m_visualizerCameraResultArgs.m_pitch,
&serverCmd.m_visualizerCameraResultArgs.m_dist,
serverCmd.m_visualizerCameraResultArgs.m_target);
serverCmd.m_type = result ? CMD_REQUEST_OPENGL_VISUALIZER_CAMERA_COMPLETED: CMD_REQUEST_OPENGL_VISUALIZER_CAMERA_FAILED; serverCmd.m_type = result ? CMD_REQUEST_OPENGL_VISUALIZER_CAMERA_COMPLETED: CMD_REQUEST_OPENGL_VISUALIZER_CAMERA_FAILED;
hasStatus = true; hasStatus = true;
break; break;

View File

@@ -1021,9 +1021,9 @@ public:
m_childGuiHelper->resetCamera(camDist,yaw,pitch,camPosX,camPosY,camPosZ); m_childGuiHelper->resetCamera(camDist,yaw,pitch,camPosX,camPosY,camPosZ);
} }
virtual bool getCameraInfo(int* width, int* height, float viewMatrix[16], float projectionMatrix[16], float camUp[3], float camForward[3],float hor[3], float vert[3] ) const virtual bool getCameraInfo(int* width, int* height, float viewMatrix[16], float projectionMatrix[16], float camUp[3], float camForward[3],float hor[3], float vert[3], float* yaw, float* pitch, float* camDist, float camTarget[3]) const
{ {
return m_childGuiHelper->getCameraInfo(width,height,viewMatrix,projectionMatrix,camUp,camForward,hor,vert); return m_childGuiHelper->getCameraInfo(width,height,viewMatrix,projectionMatrix,camUp,camForward,hor,vert,yaw,pitch,camDist,camTarget);
} }

View File

@@ -286,6 +286,11 @@ struct b3OpenGLVisualizerCameraInfo
float m_horizontal[3]; float m_horizontal[3];
float m_vertical[3]; float m_vertical[3];
float m_yaw;
float m_pitch;
float m_dist;
float m_target[3];
}; };
enum b3VREventType enum b3VREventType

View File

@@ -3925,7 +3925,7 @@ static PyObject* pybullet_getDebugVisualizerCamera(PyObject* self, PyObject* arg
if (hasCamInfo) if (hasCamInfo)
{ {
PyObject* item=0; PyObject* item=0;
pyCameraList = PyTuple_New(8); pyCameraList = PyTuple_New(12);
item = PyInt_FromLong(camera.m_width); item = PyInt_FromLong(camera.m_width);
PyTuple_SetItem(pyCameraList,0,item); PyTuple_SetItem(pyCameraList,0,item);
item = PyInt_FromLong(camera.m_height); item = PyInt_FromLong(camera.m_height);
@@ -3969,6 +3969,23 @@ static PyObject* pybullet_getDebugVisualizerCamera(PyObject* self, PyObject* arg
PyTuple_SetItem(pyCameraList,6,hor); PyTuple_SetItem(pyCameraList,6,hor);
PyTuple_SetItem(pyCameraList,7,vert); PyTuple_SetItem(pyCameraList,7,vert);
} }
item = PyFloat_FromDouble(camera.m_yaw);
PyTuple_SetItem(pyCameraList,8,item);
item = PyFloat_FromDouble(camera.m_pitch);
PyTuple_SetItem(pyCameraList,9,item);
item = PyFloat_FromDouble(camera.m_dist);
PyTuple_SetItem(pyCameraList,10,item);
{
PyObject* item=0;
int i;
PyObject* camTarget = PyTuple_New(3);
for (i=0;i<3;i++)
{
item = PyFloat_FromDouble(camera.m_target[i]);
PyTuple_SetItem(camTarget,i,item);
}
PyTuple_SetItem(pyCameraList,11,camTarget);
}
return pyCameraList; return pyCameraList;
} }