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:
@@ -17,7 +17,7 @@ subject to the following restrictions:
|
||||
|
||||
///todo: make this configurable in the gui
|
||||
bool useShadowMap = true;// true;//false;//true;
|
||||
int shadowMapWidth= 2048;//8192;
|
||||
int shadowMapWidth= 2048;
|
||||
int shadowMapHeight= 2048;
|
||||
float shadowMapWorldSize=5;
|
||||
|
||||
@@ -329,6 +329,19 @@ void GLInstancingRenderer::writeSingleInstanceTransformToCPU(const float* positi
|
||||
}
|
||||
|
||||
|
||||
void GLInstancingRenderer::readSingleInstanceTransformFromCPU(int srcIndex, float* position, float* orientation)
|
||||
{
|
||||
b3Assert(srcIndex<m_data->m_totalNumInstances);
|
||||
b3Assert(srcIndex>=0);
|
||||
position[0] = m_data->m_instance_positions_ptr[srcIndex*4+0];
|
||||
position[1] = m_data->m_instance_positions_ptr[srcIndex*4+1];
|
||||
position[2] = m_data->m_instance_positions_ptr[srcIndex*4+2];
|
||||
|
||||
orientation[0] = m_data->m_instance_quaternion_ptr[srcIndex*4+0];
|
||||
orientation[1] = m_data->m_instance_quaternion_ptr[srcIndex*4+1];
|
||||
orientation[2] = m_data->m_instance_quaternion_ptr[srcIndex*4+2];
|
||||
orientation[3] = m_data->m_instance_quaternion_ptr[srcIndex*4+3];
|
||||
}
|
||||
void GLInstancingRenderer::writeSingleInstanceColorToCPU(double* color, int srcIndex)
|
||||
{
|
||||
m_data->m_instance_colors_ptr[srcIndex*4+0]=float(color[0]);
|
||||
|
||||
Reference in New Issue
Block a user