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:
erwincoumans
2016-11-17 15:15:52 -08:00
parent ee7a5a470f
commit 8c69fa13ca
11 changed files with 664 additions and 261 deletions

View File

@@ -138,12 +138,14 @@ struct RequestPixelDataArgs
int m_startPixelIndex;
int m_pixelWidth;
int m_pixelHeight;
float m_lightDirection[3];
};
enum EnumRequestPixelDataUpdateFlags
{
REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES=1,
REQUEST_PIXEL_ARGS_SET_PIXEL_WIDTH_HEIGHT=4,
REQUEST_PIXEL_ARGS_SET_LIGHT_DIRECTION=8,
//don't exceed (1<<15), because this enum is shared with EnumRenderer in SharedMemoryPublic.h
};