add pybullet getCameraImage, replacing renderImage, cleaner API:
always pass in width, hight and viewMatrix, projectionMatrix, optionally lightDir added helper methods computeViewMatrix, computeViewMatrixFromYawPitchRoll, computeProjectionMatrix, computeProjectionMatrixFOV see Bullet/examples/pybullet/testrender.py + testrender_np.py for example use add missing base_link.stl for husky.urdf
This commit is contained in:
@@ -1416,6 +1416,10 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
{
|
||||
// printf("-------------------------------\nRendering\n");
|
||||
|
||||
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_LIGHT_DIRECTION) != 0)
|
||||
{
|
||||
m_data->m_visualConverter.setLightDirection(clientCmd.m_requestPixelDataArguments.m_lightDirection[0], clientCmd.m_requestPixelDataArguments.m_lightDirection[1], clientCmd.m_requestPixelDataArguments.m_lightDirection[2]);
|
||||
}
|
||||
|
||||
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES)!=0)
|
||||
{
|
||||
|
||||
Reference in New Issue
Block a user