diff options
author | WenlongLu <wenlong.will.lu@gmail.com> | 2020-11-11 22:41:33 -0800 |
---|---|---|
committer | WenlongLu <wenlong.will.lu@gmail.com> | 2020-11-11 22:41:33 -0800 |
commit | 21836afb9765bdca29a8496be5273c876a8e457f (patch) | |
tree | 5739843bc37e71b2512bd458ba3fdc9f3f958928 | |
parent | 56b42925d8b046c69877c983827ecdba3f19d8dd (diff) | |
download | bullet3-21836afb9765bdca29a8496be5273c876a8e457f.tar.gz |
Add share memory commands for user to change object dynamic types
-rw-r--r-- | examples/SharedMemory/PhysicsClientC_API.cpp | 11 | ||||
-rw-r--r-- | examples/SharedMemory/PhysicsClientC_API.h | 2 | ||||
-rw-r--r-- | examples/SharedMemory/PhysicsServerCommandProcessor.cpp | 42 | ||||
-rw-r--r-- | examples/SharedMemory/SharedMemoryCommands.h | 3 | ||||
-rw-r--r-- | examples/SharedMemory/SharedMemoryPublic.h | 8 |
5 files changed, 65 insertions, 1 deletions
diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index 5906d82f1..829eeca56 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -3219,6 +3219,17 @@ B3_SHARED_API int b3ChangeDynamicsInfoSetJointLimitForce(b3SharedMemoryCommandHa return 0; } +B3_SHARED_API int b3ChangeDynamicsInfoSetDynamicType(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, int dynamicType) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle; + b3Assert(command->m_type == CMD_CHANGE_DYNAMICS_INFO); + b3Assert(dynamicType == eDynamic || dynamicType == eStatic || dynamicType == eKinematic); + command->m_changeDynamicsInfoArgs.m_bodyUniqueId = bodyUniqueId; + command->m_changeDynamicsInfoArgs.m_linkIndex = linkIndex; + command->m_changeDynamicsInfoArgs.m_dynamicType = dynamicType; + command->m_updateFlags |= CHANGE_DYNAMICS_INFO_SET_DYNAMIC_TYPE; + return 0; +} diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index cd35502fb..318263b2d 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -155,7 +155,7 @@ extern "C" B3_SHARED_API int b3ChangeDynamicsInfoSetAnisotropicFriction(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, const double anisotropicFriction[]); B3_SHARED_API int b3ChangeDynamicsInfoSetJointLimit(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double jointLowerLimit, double jointUpperLimit); B3_SHARED_API int b3ChangeDynamicsInfoSetJointLimitForce(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double jointLimitForce); - + B3_SHARED_API int b3ChangeDynamicsInfoSetDynamicType(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, int dynamicType); B3_SHARED_API int b3ChangeDynamicsInfoSetLateralFriction(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkIndex, double lateralFriction); diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index fa6506643..c6cef7397 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -9713,6 +9713,17 @@ bool PhysicsServerCommandProcessor::processChangeDynamicsInfoCommand(const struc } } } + if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_DYNAMIC_TYPE) + { + int dynamic_type = clientCmd.m_changeDynamicsInfoArgs.m_dynamicType; + mb->setBaseDynamicType(dynamic_type); + + bool isDynamic = dynamic_type == eDynamic; + int collisionFilterGroup = isDynamic ? int(btBroadphaseProxy::DefaultFilter) : int(btBroadphaseProxy::StaticFilter); + int collisionFilterMask = isDynamic ? int(btBroadphaseProxy::AllFilter) : int(btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter); + m_data->m_dynamicsWorld->removeCollisionObject(mb->getBaseCollider()); + m_data->m_dynamicsWorld->addCollisionObject(mb->getBaseCollider(), collisionFilterGroup, collisionFilterMask); + } } else { @@ -9859,7 +9870,17 @@ bool PhysicsServerCommandProcessor::processChangeDynamicsInfoCommand(const struc { mb->getLinkCollider(linkIndex)->setContactProcessingThreshold(clientCmd.m_changeDynamicsInfoArgs.m_contactProcessingThreshold); } + if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_DYNAMIC_TYPE) + { + int dynamic_type = clientCmd.m_changeDynamicsInfoArgs.m_dynamicType; + mb->setLinkDynamicType(linkIndex, dynamic_type); + bool isDynamic = dynamic_type == eDynamic; + int collisionFilterGroup = isDynamic ? int(btBroadphaseProxy::DefaultFilter) : int(btBroadphaseProxy::StaticFilter); + int collisionFilterMask = isDynamic ? int(btBroadphaseProxy::AllFilter) : int(btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter); + m_data->m_dynamicsWorld->removeCollisionObject(mb->getLinkCollider(linkIndex)); + m_data->m_dynamicsWorld->addCollisionObject(mb->getLinkCollider(linkIndex), collisionFilterGroup, collisionFilterMask); + } } } } @@ -9987,6 +10008,22 @@ bool PhysicsServerCommandProcessor::processChangeDynamicsInfoCommand(const struc { rb->getCollisionShape()->setMargin(clientCmd.m_changeDynamicsInfoArgs.m_collisionMargin); } + if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_DYNAMIC_TYPE) + { + int dynamic_type = clientCmd.m_changeDynamicsInfoArgs.m_dynamicType; + // If mass is zero, the object cannot be set to be dynamic. + if (!(rb->getInvMass() != btScalar(0.) || dynamic_type != eDynamic)) { + int collision_flags = rb->getCollisionFlags(); + collision_flags &= ~(btCollisionObject::CF_STATIC_OBJECT | btCollisionObject::CF_KINEMATIC_OBJECT); + collision_flags |= dynamic_type; + rb->setCollisionFlags(collision_flags); + bool isDynamic = dynamic_type == eDynamic; + int collisionFilterGroup = isDynamic ? int(btBroadphaseProxy::DefaultFilter) : int(btBroadphaseProxy::StaticFilter); + int collisionFilterMask = isDynamic ? int(btBroadphaseProxy::AllFilter) : int(btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter); + m_data->m_dynamicsWorld->removeCollisionObject(rb); + m_data->m_dynamicsWorld->addCollisionObject(rb, collisionFilterGroup, collisionFilterMask); + } + } } } #ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD @@ -10067,6 +10104,7 @@ bool PhysicsServerCommandProcessor::processGetDynamicsInfoCommand(const struct S serverCmd.m_dynamicsInfo.m_ccdSweptSphereRadius = mb->getBaseCollider()->getCcdSweptSphereRadius(); serverCmd.m_dynamicsInfo.m_frictionAnchor = mb->getBaseCollider()->getCollisionFlags() & btCollisionObject::CF_HAS_FRICTION_ANCHOR; serverCmd.m_dynamicsInfo.m_collisionMargin = mb->getBaseCollider()->getCollisionShape()->getMargin(); + serverCmd.m_dynamicsInfo.m_dynamicType = mb->getBaseCollider()->getCollisionFlags() & (btCollisionObject::CF_STATIC_OBJECT | btCollisionObject::CF_KINEMATIC_OBJECT); } else { @@ -10075,6 +10113,7 @@ bool PhysicsServerCommandProcessor::processGetDynamicsInfoCommand(const struct S serverCmd.m_dynamicsInfo.m_ccdSweptSphereRadius = 0; serverCmd.m_dynamicsInfo.m_frictionAnchor = 0; serverCmd.m_dynamicsInfo.m_collisionMargin = 0; + serverCmd.m_dynamicsInfo.m_dynamicType = 0; } serverCmd.m_dynamicsInfo.m_localInertialDiagonal[0] = mb->getBaseInertia()[0]; serverCmd.m_dynamicsInfo.m_localInertialDiagonal[1] = mb->getBaseInertia()[1]; @@ -10118,6 +10157,7 @@ bool PhysicsServerCommandProcessor::processGetDynamicsInfoCommand(const struct S serverCmd.m_dynamicsInfo.m_ccdSweptSphereRadius = mb->getLinkCollider(linkIndex)->getCcdSweptSphereRadius(); serverCmd.m_dynamicsInfo.m_frictionAnchor = mb->getLinkCollider(linkIndex)->getCollisionFlags() & btCollisionObject::CF_HAS_FRICTION_ANCHOR; serverCmd.m_dynamicsInfo.m_collisionMargin = mb->getLinkCollider(linkIndex)->getCollisionShape()->getMargin(); + serverCmd.m_dynamicsInfo.m_dynamicType = mb->getLinkCollider(linkIndex)->getCollisionFlags() & (btCollisionObject::CF_STATIC_OBJECT | btCollisionObject::CF_KINEMATIC_OBJECT); } else { @@ -10126,6 +10166,7 @@ bool PhysicsServerCommandProcessor::processGetDynamicsInfoCommand(const struct S serverCmd.m_dynamicsInfo.m_ccdSweptSphereRadius = 0; serverCmd.m_dynamicsInfo.m_frictionAnchor = 0; serverCmd.m_dynamicsInfo.m_collisionMargin = 0; + serverCmd.m_dynamicsInfo.m_dynamicType = 0; } serverCmd.m_dynamicsInfo.m_localInertialDiagonal[0] = mb->getLinkInertia(linkIndex)[0]; @@ -10183,6 +10224,7 @@ bool PhysicsServerCommandProcessor::processGetDynamicsInfoCommand(const struct S serverCmd.m_dynamicsInfo.m_linearDamping = rb->getLinearDamping(); serverCmd.m_dynamicsInfo.m_mass = rb->getMass(); serverCmd.m_dynamicsInfo.m_collisionMargin = rb->getCollisionShape() ? rb->getCollisionShape()->getMargin() : 0; + serverCmd.m_dynamicsInfo.m_dynamicType = rb->getCollisionFlags() & (btCollisionObject::CF_STATIC_OBJECT | btCollisionObject::CF_KINEMATIC_OBJECT); } #ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD else if (body && body->m_softBody) diff --git a/examples/SharedMemory/SharedMemoryCommands.h b/examples/SharedMemory/SharedMemoryCommands.h index 197dbc0c6..a019a58ca 100644 --- a/examples/SharedMemory/SharedMemoryCommands.h +++ b/examples/SharedMemory/SharedMemoryCommands.h @@ -173,6 +173,7 @@ enum EnumChangeDynamicsInfoFlags CHANGE_DYNAMICS_INFO_SET_COLLISION_MARGIN = 1 << 17, CHANGE_DYNAMICS_INFO_SET_JOINT_LIMITS = 1 << 18, CHANGE_DYNAMICS_INFO_SET_JOINT_LIMIT_MAX_FORCE = 1 << 19, + CHANGE_DYNAMICS_INFO_SET_DYNAMIC_TYPE = 1 << 20, }; struct ChangeDynamicsInfoArgs @@ -202,6 +203,8 @@ struct ChangeDynamicsInfoArgs double m_jointLowerLimit; double m_jointUpperLimit; double m_jointLimitForce; + + int m_dynamicType; }; struct GetDynamicsInfoArgs diff --git a/examples/SharedMemory/SharedMemoryPublic.h b/examples/SharedMemory/SharedMemoryPublic.h index 46c69fe07..775f9f708 100644 --- a/examples/SharedMemory/SharedMemoryPublic.h +++ b/examples/SharedMemory/SharedMemoryPublic.h @@ -395,6 +395,7 @@ struct b3DynamicsInfo double m_contactProcessingThreshold; int m_frictionAnchor; double m_collisionMargin; + int m_dynamicType; }; // copied from btMultiBodyLink.h @@ -1070,6 +1071,13 @@ struct b3ForwardDynamicsAnalyticsArgs struct b3ForwardDynamicsAnalyticsIslandData m_islandData[MAX_ISLANDS_ANALYTICS]; }; +enum eDynamicTypes +{ + eDynamic= 0, + eStatic= 1, + eKinematic= 2 +}; + enum eFileIOActions { eAddFileIOAction = 1024,//avoid collision with eFileIOTypes |