Merge pull request #772 from erwincoumans/master

merge pybullet, make husky wheels soft/compliant as a test.
This commit is contained in:
erwincoumans
2016-09-08 12:41:06 -07:00
committed by GitHub
4 changed files with 35 additions and 6 deletions

View File

@@ -102,6 +102,13 @@ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSI
</gazebo>
<!-- Husky wheel macros -->
<link name="front_left_wheel_link">
<contact>
<lateral_friction value="1.0"/>
<rolling_friction value="0.0"/>
<stiffness value="30000"/>
<damping value="1000"/>
</contact>
<inertial>
<mass value="2.637"/>
<origin xyz="0 0 0"/>
@@ -146,6 +153,13 @@ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSI
</joint>
</transmission>
<link name="front_right_wheel_link">
<contact>
<lateral_friction value="1.0"/>
<rolling_friction value="0.0"/>
<stiffness value="30000"/>
<damping value="1000"/>
</contact>
<inertial>
<mass value="2.637"/>
<origin xyz="0 0 0"/>
@@ -190,6 +204,13 @@ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSI
</joint>
</transmission>
<link name="rear_left_wheel_link">
<contact>
<lateral_friction value="1.0"/>
<rolling_friction value="0.0"/>
<stiffness value="30000"/>
<damping value="1000"/>
</contact>
<inertial>
<mass value="2.637"/>
<origin xyz="0 0 0"/>
@@ -234,6 +255,13 @@ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSI
</joint>
</transmission>
<link name="rear_right_wheel_link">
<contact>
<lateral_friction value="1.0"/>
<rolling_friction value="0.0"/>
<stiffness value="30000"/>
<damping value="1000"/>
</contact>
<inertial>
<mass value="2.637"/>
<origin xyz="0 0 0"/>

View File

@@ -17,9 +17,9 @@ subject to the following restrictions:
///todo: make this configurable in the gui
bool useShadowMap = true;// true;//false;//true;
int shadowMapWidth=4096;//8192;
int shadowMapHeight= 4096;
float shadowMapWorldSize=25;
int shadowMapWidth= 2048;//8192;
int shadowMapHeight= 2048;
float shadowMapWorldSize=5;
#define MAX_POINTS_IN_BATCH 1024
#define MAX_LINES_IN_BATCH 1024
@@ -1475,7 +1475,7 @@ void GLInstancingRenderer::renderSceneInternal(int renderMode)
// m_data->m_shadowMap->disable();
// return;
glEnable(GL_CULL_FACE);
glCullFace(GL_BACK); // Cull back-facing triangles -> draw only front-facing triangles
glCullFace(GL_FRONT); // Cull back-facing triangles -> draw only front-facing triangles
b3Assert(glGetError() ==GL_NO_ERROR);
} else

View File

@@ -139,6 +139,7 @@ void MotionThreadFunc(void* userPtr,void* lsMemory)
skip++;
skip1++;
if (skip1>5)
{
b3Clock::usleep(250);
}

View File

@@ -971,7 +971,7 @@ static PyObject* pybullet_getContactPointData(PyObject* self, PyObject* args) {
struct b3ContactInformation contactPointData;
b3SharedMemoryStatusHandle statusHandle;
int statusType;
int i;
PyObject* pyResultList = 0;
if (size == 1) {
@@ -991,7 +991,7 @@ static PyObject* pybullet_getContactPointData(PyObject* self, PyObject* args) {
b3SetContactFilterBodyA(commandHandle, objectUniqueIdA);
b3SetContactFilterBodyB(commandHandle, objectUniqueIdB);
b3SubmitClientCommand(sm, commandHandle);
int i;
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
statusType = b3GetStatusType(statusHandle);
if (statusType == CMD_CONTACT_POINT_INFORMATION_COMPLETED) {