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

@@ -32,7 +32,8 @@ struct TinyRendererVisualShapeConverter : public LinkVisualShapesConverter
void getWidthAndHeight(int& width, int& height);
void setWidthAndHeight(int width, int height);
void setLightDirection(float x, float y, float z);
void copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels,int* segmentationMaskBuffer, int segmentationMaskSizeInPixels, int startPixelIndex, int* widthPtr, int* heightPtr, int* numPixelsCopied);
void render();