Improve debug text/line rendering, can be use to draw frames and text in local coordinate of an object / link.
example:
kuka = p.loadURDF("kuka_iiwa/model.urdf")
p.getNumJoints(kuka)
pybullet.addUserDebugLine([0,0,0],[0,0,0.1],[0,0,1],trackObjectUniqueId=2,trackLinkIndex=6)
pybullet.addUserDebugText("tip", [0,0,0.1],textColorRGB=[1,0,0],trackObjectUniqueId=2,trackLinkIndex=6)
Also allow to render text using a given orientation (instead of pointing to the camera), example:
pybullet.addUserDebugText("tip", [0,0,0.1],textColorRGB=[1,0,0],textOrientation=[0,0,0,1], trackObjectUniqueId=2,trackLinkIndex=6)
Add drawTexturedTriangleMesh, for drawing 3d text.
Expose readSingleInstanceTransformToCPU, to extract position/orientation from graphics index.
updateTexture: allow to not flip texels around up axis
This commit is contained in:
@@ -64,8 +64,8 @@ public:
|
||||
///vertices must be in the format x,y,z, nx,ny,nz, u,v
|
||||
virtual int registerShape(const float* vertices, int numvertices, const int* indices, int numIndices, int primitiveType=B3_GL_TRIANGLES, int textureIndex=-1);
|
||||
|
||||
virtual int registerTexture(const unsigned char* texels, int width, int height);
|
||||
virtual void updateTexture(int textureIndex, const unsigned char* texels);
|
||||
virtual int registerTexture(const unsigned char* texels, int width, int height, bool flipPixelsY=true);
|
||||
virtual void updateTexture(int textureIndex, const unsigned char* texels, bool flipPixelsY=true);
|
||||
virtual void activateTexture(int textureIndex);
|
||||
|
||||
|
||||
@@ -76,7 +76,8 @@ public:
|
||||
|
||||
void writeTransforms();
|
||||
|
||||
|
||||
virtual bool readSingleInstanceTransformToCPU(float* position, float* orientation, int srcIndex);
|
||||
|
||||
virtual void writeSingleInstanceTransformToCPU(const float* position, const float* orientation, int srcIndex);
|
||||
virtual void writeSingleInstanceTransformToCPU(const double* position, const double* orientation, int srcIndex)
|
||||
{
|
||||
@@ -113,6 +114,8 @@ public:
|
||||
virtual void drawPoints(const float* positions, const float color[4], int numPoints, int pointStrideInBytes, float pointDrawSize);
|
||||
virtual void drawPoint(const float* position, const float color[4], float pointSize=1);
|
||||
virtual void drawPoint(const double* position, const double color[4], double pointDrawSize=1);
|
||||
virtual void drawTexturedTriangleMesh(float worldPosition[3], float worldOrientation[4], const float* vertices, int numvertices, const unsigned int* indices, int numIndices, float color[4], int textureIndex=-1);
|
||||
|
||||
virtual void updateCamera(int upAxis=1);
|
||||
|
||||
virtual const CommonCameraInterface* getActiveCamera() const;
|
||||
|
||||
Reference in New Issue
Block a user