Bullet物理引擎调研

Bullet物理引擎调研

1 总览

Bullet,是一个实时物理仿真引擎,在VR、游戏、视觉特效、机器人、机器学习等领域都有应用。Bullet的著名客户包括侠盗飞车5、荒野大镖客、闪电狗、Blender、Cinema 4D等等。

侠盗飞车5

评价物理引擎主要有四方面的指标,性能、仿真精度、功能广度、易用性。鱼和熊掌不可兼得,各个物理引擎主要的差别就在于对这些方面进行了不同的取舍。Bullet文档中写道“Bullet is physics simulation software, in particular for rigid body dynamics and collision detection”,其主要的侧重点在于刚体模拟、碰撞检测和易用性,从官网的动态来看近来比较受科研工作者的喜爱(如机器人仿真方向的研究团队Google Brain, Stanford AI Lab, Open AI)。

但因为Bullet是一个没有商业机构运作的引擎,仅仅依靠开源社区支持,所以相比其他引擎,它的功能较少、代码及文档质量不佳,这使得其在商用方面逐渐式微[1]。并且其在OpenCL并行加速方面的工作还处于Experimental的状态,可能整体性能不如PhysX、Havok等引擎。

下面列举一下官方的“王婆卖瓜,自卖自夸”(译自官方源码中提供的文档Bullet_User_Manual),可以比较直观的了解Bullet引擎的特性:

  • 同时支持离散(Discrete)及连续(Continuous)碰撞检测以及射线及凸扫描测试(convex sweep test)。引擎支持的碰撞体形状包括凸状网格、凹状网格以及所有基本形状(basic primitives)。
  • 支持最高6自由度的刚体模拟及约束连接,以及基于关节体算法(Articulated body algorithm)使用移动器(mobilizers)实现的多刚体(Multibody)系统。
  • 实现了快速、稳定的刚体动力学约束解算器,车辆动力学(Vehicle Dynamics),角色控制器(Character Controller),滑块(Slider),铰链(Hinge),通用的6自由度Constrain以及用于实现布娃娃(Ragdoll)模拟的Cone Twist Constraint。
  • 使用柔体动力学实现布料、绳、可变形物的模拟,支持柔体与刚体的双向交互(Two-way Interaction),并提供了对约束(Constraint)的支持。
  • Bullet是Zlib许可下的开源项目,可以免费用于商业项目,并提供了广泛的平台支持(PS3, XBox 360, Wii, PC, Linux, Mac OSX, Android, iPhone)。
  • 提供了Maya Dynamica插件,Blender集成,原生二进制.bullet序列化等文件及辅助功能。引擎支持URDP,.obj,.bsp等格式资源的导入。
  • 提供了Example Browser示例程序展示Bullet SDK的功能。示例程序可以使用OpenGL3渲染模拟结果,也可以直接在控制台进行输出。
  • 提供了上手指南、源码文档、Wiki和论坛,能够帮助开发者更轻松地了解引擎功能。

2 架构

物理引擎的主要任务是进行碰撞检测,并根据碰撞及其他约束进行修正,最后提供一个实时更新的Transform(包括位置及旋转信息)。

Bullet的主要功能模块如下图:

Bullet功能模块图

2.1 Rigid Body Dynamics

在下图中,上半部分是流程中用到的主要数据结构,下半部分是刚体物理解算流程。蓝色箭头代表读取数据,红色箭头代表读写数据。

刚体物理数据结构及解算流程图

在Bullet引擎中,整个上述流程都被封装在dynamics world中。当对dynamics world调用 stepSimulation 方法时,就会执行一次上述解算流程。并且开发者可以根据自身需求,替换甚至是重写其中的每个部分,如broadphase collision detection,narrowphase collision detection以及constraint solver。

2.2 Collision Detection

首先是broadphase碰撞检测,会根据Axis aligned bounding box (AABB)进行重叠检测,粗略的筛选出有较大可能性碰撞的物体对(pair)。Bullet会对重叠物体对进行缓存,这样之后重复碰撞时可以使用上一次缓存的信息加速约束解析的收敛速度。

Collision dispatcher会对所有物体对进行遍历,根据它们的形状类型找到合适的碰撞算法,并执行找到的碰撞算法求出接触点(Contact Point)。

Bullet支持许多种类的形状,并给出了一个图让开发者能够直观的选择适合自身需求的类型。

形状选择指引图

Collision Dispatcher会根据物体对中双方的形状,在下表中映射到对应的解析算法,且开发者可以根据需要修改这个映射表。其中GJK全称是Gilbert, Johnson和Keerthi,他们是Convex distance calculation algorithm的发明者。GJK通常会和EPA一起使用,EPA是用于穿透深度计算的方法,全称为Expanding Polythope Algorithm,由Gina van den Bergen发明。

碰撞算法映射表

另外,Bullet还提供了Collision Filtering的机制,允许开发者去除掉指定物体之间的碰撞。

2.3 Constraints

Bullet提供了许多种Constrain的实现,以下分别列举。

2.3.1 Point to Point Constrain

Point to Point Constrain可以使两个刚体的给定轴点(pivot point)保持重合,可以用于将刚体像锁链一样连接。示例代码如下:

btPoint2PointConstraint(btRigidBody& rbA,const btVector3& pivotInA);
btPoint2PointConstraint(btRigidBody& rbA,btRigidBody& rbB, const btVector3& pivotInA,const btVector3& pivotInB);

Point to Point Constrain

2.3.2 Hinge Constrain

Hinge Constrain又叫Revolute joint,限制两个方向的旋转角度,保证刚体只能绕单个方向(即hinge axis)进行旋转,可以用来模拟门或轮胎。示例代码如下:

btHingeConstraint(btRigidBody& rbA,const btTransform& rbAFrame, bool useReferenceFrameA = false);
btHingeConstraint(btRigidBody& rbA,const btVector3& pivotInA,btVector3& axisInA, bool useReferenceFrameA = false);
btHingeConstraint(btRigidBody& rbA,btRigidBody& rbB, const btVector3& pivotInA,const btVector3& pivotInB, btVector3& axisInA, btVector3& axisInB, bool useReferenceFrameA = false);
btHingeConstraint(btRigidBody& rbA,btRigidBody& rbB, const btTransform& rbAFrame, const btTransform& rbBFrame, bool useReferenceFrameA = false);

Hinge Constrain

2.3.3 Slider Constrain

Slider Constrain限制物体只能绕单个轴进行旋转,只能沿单个轴进行平移。

btSliderConstraint(btRigidBody& rbA, btRigidBody& rbB, const btTransform& frameInA, const btTransform& frameInB, bool useLinearReferenceFrameA);

Slider Constrain

2.3.4 Cone Twist Constrain

Cone twist constrain常被用于模拟Ragdoll的四肢。It is a special point to point constraint that adds cone and twist axis limits.

btConeTwistConstraint(btRigidBody& rbA,const btTransform& rbAFrame);
btConeTwistConstraint(btRigidBody& rbA,btRigidBody& rbB, const btTransform& rbAFrame, const btTransform& rbBFrame);

2.3.5 Generic 6 Dof Constrain

开发者可以针对6个自由度(3个位置自由度,3个旋转自由度)单独设定constrain。每个自由度可以处于锁定(locked)、自由(free)和受限(limited)三种状态。

btGeneric6DofConstraint(btRigidBody& rbA, btRigidBody& rbB, const btTransform& frameInA, const btTransform& frameInB, bool useLinearReferenceFrameA);

2.4 Soft Body Dynamics

本模块在刚体动力学基础上增加了对绳、布料、体积软体(volumetric soft bodies)的支持。并且软体可以和刚体之间进行双向交互(Two-way interaction)。

使用函数 btSoftBodyHelpers::CreateFromTriMesh 可以从面片模型生成软体。默认的情况下,软体的碰撞检测是在顶点和面片之间进行的,因而需要很稠密的细分(dense tessellation)才能进行正确的碰撞检测。Bullet另外还实现了一种基于Automatic decomposition convex deformable clusters的改进方法,通过如下代码启用:

psb->generateClusters(numSubdivisions);
//enable cluster collision between soft body and rigid body
psb->m_cfg.collisions += btSoftBody::fCollision::CL_RS;
//enable cluster collision between soft body and soft body
psb->m_cfg.collisions += btSoftBody::fCollision::CL_SS;

Bullet支持对软体或软体的单个顶点施加力:

softbody ->addForce(const btVector3& forceVector);
softbody ->addForce(const btVector3& forceVector,int node);

Bullet支持对单个顶点添加约束,以实现各种效果。如固定软体中单个顶点的位置:

softbody->setMass(node,0.f);

或者将软体中某个顶点附着在刚体上:

softbody->appendAnchor(int node,btRigidBody* rigidbody, bool 
			disableCollisionBetweenLinkedBodies=false);

3 Hello World 源码分析

Bullet引擎中在 ·examples/HelloWorld/HelloWorld.cpp· 文件中提供了一个Hello World版本,也就是一个简易的Demo,能够让我们初步了解Bullet引擎的基本使用方法。

主要分为四个部分:

  • 创建dynamics world进行参数配置。
  • 添加仿真物体,并设置物体信息。
  • 循环更新逻辑,逐帧输出物体位置数据。
  • 释放分配的资源及指针。

3.1 创建Dynamics world

首先是include头文件 ·btBulletDynamicsCommon.h· 。这个文件内部包含了常用的API。

#include "btBulletDynamicsCommon.h"
#include <stdio.h>

然后创建dynamics world,并设置重力大小、使用的Solver类型以及配置等参数。

///collision configuration contains default setup for memory, collision setup. Advanced users can create their own configuration.
btDefaultCollisionConfiguration* collisionConfiguration = new btDefaultCollisionConfiguration();

///use the default collision dispatcher. For parallel processing you can use a diffent dispatcher (see Extras/BulletMultiThreaded)
btCollisionDispatcher* dispatcher = new btCollisionDispatcher(collisionConfiguration);

///btDbvtBroadphase is a good general purpose broadphase. You can also try out btAxis3Sweep.
btBroadphaseInterface* overlappingPairCache = new btDbvtBroadphase();

///the default constraint solver. For parallel processing you can use a different solver (see Extras/BulletMultiThreaded)
btSequentialImpulseConstraintSolver* solver = new btSequentialImpulseConstraintSolver;

btDiscreteDynamicsWorld* dynamicsWorld = new btDiscreteDynamicsWorld(dispatcher, overlappingPairCache, solver, collisionConfiguration);

dynamicsWorld->setGravity(btVector3(0, -10, 0));

3.2 添加仿真物体

接着就是添加需要仿真的物体,这里以Sphere为例。需要设置物体的形状、Transform、质量、运动状态(Motion State)等信息,最后添加到dynamics world中。

//btCollisionShape* colShape = new btBoxShape(btVector3(1,1,1));
btCollisionShape* colShape = new btSphereShape(btScalar(1.));
collisionShapes.push_back(colShape);

/// Create Dynamic Objects
btTransform startTransform;
startTransform.setIdentity();

btScalar mass(1.f);

//rigidbody is dynamic if and only if mass is non zero, otherwise static
bool isDynamic = (mass != 0.f);

btVector3 localInertia(0, 0, 0);
if (isDynamic)
	colShape->calculateLocalInertia(mass, localInertia);

startTransform.setOrigin(btVector3(2, 10, 0));

//using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
btDefaultMotionState* myMotionState = new btDefaultMotionState(startTransform);
btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, colShape, localInertia);
btRigidBody* body = new btRigidBody(rbInfo);

dynamicsWorld->addRigidBody(body);

3.3 循环更新

准备工作就此完成,现在就可以正式进入程序的循环更新逻辑了。主要就是遍历dynamics world中的所有物体,并输出其位置信息。具体的物理仿真逻辑都隐藏在Bullet SDK中了,开发者无需涉足。

for (i = 0; i < 150; i++)
{
	dynamicsWorld->stepSimulation(1.f / 60.f, 10);

	//print positions of all objects
	for (int j = dynamicsWorld->getNumCollisionObjects() - 1; j >= 0; j--)
	{
	btCollisionObject* obj = dynamicsWorld->getCollisionObjectArray()[j];
	btRigidBody* body = btRigidBody::upcast(obj);
	btTransform trans;
	if (body && body->getMotionState())
	{
		body->getMotionState()->getWorldTransform(trans);
	}
	else
	{
		trans = obj->getWorldTransform();
	}
	printf("world pos object %d = %f,%f,%f\n", j, 
		float(trans.getOrigin().getX()),
		float(trans.getOrigin().getY()),
		float(trans.getOrigin().getZ()));
	}
}

最后一步是释放掉各种分配的资源和指针,具体代码就不列出了。

4 功能演示

Bullet源码[2]中提供了一个Example Browser,用于浏览Bullet引擎中提供的各种实例场景,可以很直观的看到Bullet引擎提供的各类功能,并且用户可以使用鼠标拖拽移动场景中的物体进行交互。下面按照该Browser的划分来简单介绍功能。

4.1 API

展示Bullet引擎提供的基础API,如碰撞响应、摩擦力、Constrain以及各种物体类型刚体、Hinge、弹簧、陀螺仪、柔体。

Basic Example Demo

4.2 Multibody

展示多个刚体之间的交互,主要是使用关节进行连接。

Multi DOF Demo

4.3 Physics Client-Server

Bullet支持使用CS架构调用其他进程进行物理仿真计算。其他进程可以在本地运行,也可以在其他机器上运行(通过TCP/UDP网络进行通信)。

Client Server Demo

4.4 Inverse Dynamics

反向动力学。拖拽其中一个位置之后,其他关节也会被带动进行旋转。

Inverse Dynamics URDF Demo

4.5 Inverse Kinematics

反向运动学。示例程序中的物体由多个关节相连,动作像随风摇摆的树一样。Inverse Kinematics和Inverse Dynamics有一定相似之处,但是两个算法具有不同的目标和初始假设[3]。

Inverse Dynamics是给定指定点在一段时间内的位置及速度,求各关节的转矩(torques)。

Inverse Kinematics (IK)要计算的则是保证指定点处于指定位置的情况下,各关节的旋转度数。IK经常被用于进行骨骼动画和物理的融合,常用于游戏及Robotics。

Inverse Kinematics SDLS Demo

4.6 Deformable Body

主要是可变形物体的展示,如布料(自碰撞、摩擦力)、可变形物体以及可变形物体与刚体的交互。

Deformable Self Collision Demo

4.7 Soft Body

柔体的模拟,好像和Deformable Body就是一样的东西,不知道为什么会单独列出。包括布料、柔体、体积/压强约束、绳子的模拟,同时也有一个空气动力学的Demo。

Cloth Demo

4.8 Benchmarks

小方块碰撞性能测试。3000个小方块从空中落下、碰撞并散开。支持多线程和SIMD加速。

3000 Boxes Demo

4.9 Importers

展示Bullet引擎为各类文件格式提供的导入器,包括自己的.bullet格式以及其他常用格式如URDF(Unified Robot Description Format),MJCF(Multi-Joint Dynamics with Contact Format),SDF(Spatial Data File)等文件。这些文件主要是储存场景物体模型及状态信息。

Import .bullet Demo

4.10 Raycast

射线功能被广泛应用于游戏等应用,实现鼠标选中三维物体等功能。在示例场景中,一条水平方向的射线在垂直方向上下移动,并显示该射线在场景物体上的交点及交点位置处的法线。

Raytest Demo

4.11 Experiments

夹子模拟。类似于抓娃娃机一样的行为,使用一个夹子抓取地面上的方块。

Gripper Grasp Demo

4.12 Rendering

Bullet SDK同时支持CPU渲染及GPU渲染。

Tiny Renderer Demo

4.13 Evolution

神经网络驱动的自动行走的小蜘蛛。

Neural Network 3D Walkers Demo

5 “前车之鉴”

最后大致总结一下Bullet引擎中值得参考和学习的地方:

  • 开发语言。Bullet引擎本体使用C++进行开发,目前正在开发PyBullet,将接口暴露在Python语言中,通过pip install命令即可安装,让开发者能够更轻松的上手。
  • 编译工具。Bullet同时支持Premake[4]和CMake[5]两种方式。
  • 源码文档。Bullet使用了Doxygen[6]实现源码文档的自动生成。
  • 接口设计。基础方面Bullet将整个物理引擎分割为了许多的模块如Configuration,Broadphase,Narrowphase等,每个模块都提供了几种默认类型供选择,开发者也可以自己继承基类实现自己的计算方法。并且Bullet加入了许多callback支持开发者的自定义行为。
  • 物理引擎实现原理。Bullet官网列出了与其实现相关的三个SIGGRAPH 2015 course的slides[7][8][9],讲解了物理引擎的基本实现原理、优化算法和并行加速。

6 References

  1. 为什么Physx会成为目前大部分主流游戏引擎的选择,相比较bullet优势在哪里?. https://www.zhihu.com/question/309154499/answer/578649506
  2. bulletphysics/bullet3 源码. https://github.com/bulletphysics/bullet3
  3. Inverse Dynamics – Wikipedia. https://en.wikipedia.org/wiki/Inverse_dynamics
  4. Premake: Powerfully simple build configuration. https://premake.github.io/
  5. CMake: An open-source, cross-platform family of tools designed to build, test and package software. https://cmake.org/
  6. Doxygen: Generate documentation from source code. http://www.doxygen.nl/
  7. Introduction to rigid body pipeline, collision detection. https://docs.google.com/presentation/d/1-UqEzGEHdskq8blwNWqdgnmUDwZDPjlZUvg437z7XCM/edit#slide=id.ga4b37291a_0_0
  8. Advances in constraint solving, Featherstone Articulated Body Algorithm. https://docs.google.com/presentation/d/1wGUJ4neOhw5i4pQRfSGtZPE3CIm7MfmqfTp5aJKuFYM/edit#slide=id.ga4b37291a_0_0
  9. Acceleration of the full collision detection and constraint solver on GPU. https://docs.google.com/presentation/d/1BW5-2ADy88-Eo_v_bknTNDOoBNYjRL4XCF_tYLYUL3g/edit#slide=id.ga4b37291a_0_0

评论

Your browser is out-of-date!

Update your browser to view this website correctly. Update my browser now

×