This commit is contained in:
Erwin Coumans
2017-05-12 17:18:10 -07:00
4 changed files with 59 additions and 38 deletions

View File

@@ -4536,7 +4536,6 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
int linkIndexB = -1;
int objectIndexB = -1;
const btRigidBody* bodyB = btRigidBody::upcast(manifold->getBody1());
if (bodyB)
{
@@ -4547,12 +4546,6 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
{
linkIndexB = mblB->m_link;
objectIndexB = mblB->m_multiBody->getUserIndex2();
if (
(clientCmd.m_updateFlags & CMD_REQUEST_CONTACT_POINT_HAS_LINK_INDEX_B_FILTER) &&
clientCmd.m_requestContactPointArguments.m_linkIndexBIndexFilter != linkIndexB)
{
continue;
}
}
int objectIndexA = -1;
@@ -4566,30 +4559,55 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
{
linkIndexA = mblA->m_link;
objectIndexA = mblA->m_multiBody->getUserIndex2();
if (
(clientCmd.m_updateFlags & CMD_REQUEST_CONTACT_POINT_HAS_LINK_INDEX_A_FILTER) &&
clientCmd.m_requestContactPointArguments.m_linkIndexAIndexFilter != linkIndexA)
}
btAssert(bodyA || mblA);
//apply the filter, if the user provides it
bool swap = false;
if (clientCmd.m_requestContactPointArguments.m_objectAIndexFilter >= 0)
{
if (clientCmd.m_requestContactPointArguments.m_objectAIndexFilter == objectIndexA)
{
swap = false;
}
else if (clientCmd.m_requestContactPointArguments.m_objectAIndexFilter == objectIndexB)
{
swap = true;
}
else
{
continue;
}
}
btAssert(bodyA || mblA);
//apply the filter, if the user provides it
if (clientCmd.m_requestContactPointArguments.m_objectAIndexFilter >= 0)
if (swap)
{
if ((clientCmd.m_requestContactPointArguments.m_objectAIndexFilter != objectIndexA) &&
(clientCmd.m_requestContactPointArguments.m_objectAIndexFilter != objectIndexB))
continue;
std::swap(objectIndexA, objectIndexB);
std::swap(linkIndexA, linkIndexB);
std::swap(bodyA, bodyB);
}
//apply the second object filter, if the user provides it
if (clientCmd.m_requestContactPointArguments.m_objectBIndexFilter >= 0)
{
if ((clientCmd.m_requestContactPointArguments.m_objectBIndexFilter != objectIndexA) &&
(clientCmd.m_requestContactPointArguments.m_objectBIndexFilter != objectIndexB))
if (clientCmd.m_requestContactPointArguments.m_objectBIndexFilter != objectIndexB)
{
continue;
}
}
if (
(clientCmd.m_updateFlags & CMD_REQUEST_CONTACT_POINT_HAS_LINK_INDEX_A_FILTER) &&
clientCmd.m_requestContactPointArguments.m_linkIndexAIndexFilter != linkIndexA)
{
continue;
}
if (
(clientCmd.m_updateFlags & CMD_REQUEST_CONTACT_POINT_HAS_LINK_INDEX_B_FILTER) &&
clientCmd.m_requestContactPointArguments.m_linkIndexBIndexFilter != linkIndexB)
{
continue;
}
for (int p = 0; p < manifold->getNumContacts(); p++)

View File

@@ -50,7 +50,9 @@ dummy.initial_z = None
def current_relative_position(human, j, lower, upper):
#print("j")
#print(j)
pos, vel, *other = p.getJointState(human, j)
temp = p.getJointState(human, j)
pos = temp[0]
vel = temp[1]
#print("pos")
#print(pos)
#print("vel")

View File

@@ -417,7 +417,7 @@ else:
setup(
name = 'pybullet',
version='1.0.2',
version='1.0.3',
description='Official Python Interface for the Bullet Physics SDK Robotics Simulator',
long_description='pybullet is an easy to use Python module for physics simulation, robotics and machine learning based on the Bullet Physics SDK. With pybullet you can load articulated bodies from URDF, SDF and other file formats. pybullet provides forward dynamics simulation, inverse dynamics computation, forward and inverse kinematics and collision detection and ray intersection queries. Aside from physics simulation, pybullet supports to rendering, with a CPU renderer and OpenGL visualization and support for virtual reality headsets.',
url='https://github.com/bulletphysics/bullet3',

View File

@@ -4,8 +4,8 @@ Copyright (c) 2013 Erwin Coumans http://bulletphysics.org
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
@@ -74,17 +74,12 @@ public:
if (m_link>=0)
{
const btMultibodyLink& link = m_multiBody->getLink(this->m_link);
if (link.m_flags&BT_MULTIBODYLINKFLAGS_DISABLE_PARENT_COLLISION)
{
if ( link.m_parent == other->m_link)
return false;
}
if (link.m_flags&BT_MULTIBODYLINKFLAGS_DISABLE_ALL_PARENT_COLLISION)
{
int parent_of_this = m_link;
while (1)
while (1)
{
if (parent_of_this==-1)
if (parent_of_this==-1)
break;
parent_of_this = m_multiBody->getLink(parent_of_this).m_parent;
if (parent_of_this==other->m_link)
@@ -93,28 +88,34 @@ public:
}
}
}
else if (link.m_flags&BT_MULTIBODYLINKFLAGS_DISABLE_PARENT_COLLISION)
{
if ( link.m_parent == other->m_link)
return false;
}
}
if (other->m_link>=0)
{
const btMultibodyLink& otherLink = other->m_multiBody->getLink(other->m_link);
if (otherLink.m_flags& BT_MULTIBODYLINKFLAGS_DISABLE_PARENT_COLLISION)
{
if (otherLink.m_parent == this->m_link)
return false;
}
if (otherLink.m_flags& BT_MULTIBODYLINKFLAGS_DISABLE_ALL_PARENT_COLLISION)
{
int parent_of_other = other->m_link;
while (1)
while (1)
{
if (parent_of_other==-1)
if (parent_of_other==-1)
break;
parent_of_other = m_multiBody->getLink(parent_of_other).m_parent;
if (parent_of_other==this->m_link)
return false;
}
}
else if (otherLink.m_flags& BT_MULTIBODYLINKFLAGS_DISABLE_PARENT_COLLISION)
{
if (otherLink.m_parent == this->m_link)
return false;
}
}
return true;
}