Create project file for BussIK inverse kinematics library (premake, cmake)
URDF/SDF: add a flag to force concave mesh collisiofor static objects. <collision concave="yes" name="pod_collision"> VR: support teleporting using buttong, allow multiple controllers to be used, fast wireframe rendering, Turn off warnings about deprecated C routine in btScalar.h/b3Scalar.h Add a dummy return to stop a warning Expose defaultContactERP in shared memory api/pybullet. First start to expose IK in shared memory api/pybullet (not working yet)
This commit is contained in:
@@ -41,7 +41,7 @@ class GLInstancingRenderer : public CommonRenderInterface
|
||||
int m_upAxis;
|
||||
bool m_enableBlend;
|
||||
|
||||
void renderSceneInternal(int renderMode=B3_DEFAULT_RENDERMODE);
|
||||
|
||||
|
||||
|
||||
|
||||
@@ -52,6 +52,7 @@ public:
|
||||
virtual void init();
|
||||
|
||||
virtual void renderScene();
|
||||
virtual void renderSceneInternal(int renderMode=B3_DEFAULT_RENDERMODE);
|
||||
|
||||
void InitShaders();
|
||||
void CleanupShaders();
|
||||
@@ -73,6 +74,7 @@ public:
|
||||
|
||||
void writeTransforms();
|
||||
|
||||
|
||||
virtual void writeSingleInstanceTransformToCPU(const float* position, const float* orientation, int srcIndex);
|
||||
virtual void writeSingleInstanceTransformToCPU(const double* position, const double* orientation, int srcIndex)
|
||||
{
|
||||
@@ -90,6 +92,8 @@ public:
|
||||
|
||||
}
|
||||
|
||||
virtual void readSingleInstanceTransformFromCPU(int srcIndex, float* position, float* orientation);
|
||||
|
||||
virtual void writeSingleInstanceTransformToGPU(float* position, float* orientation, int srcIndex);
|
||||
|
||||
virtual void writeSingleInstanceColorToCPU(float* color, int srcIndex);
|
||||
|
||||
Reference in New Issue
Block a user