simulate(2)
我们在上一节中,从 main 函数开始,分析了官方提供的仿真器 simulate 的仿真推演的线程。 这个线程基本上是编程套路进行的,在一个超级循环中通过 mj_step 完成正动力学和数值积分。 本节,我们具体分析响应 UI 交互并完成图形渲染的这个线程。
1. Simulate()
在 simulate 中,对UI的交互响应和图形渲染被封装到一个类 Simulate 中了。我个人比较习惯从构造函数和析构函数入手分析一个类。 下面是该类构造函数的代码片段,它有 5 个输入参数。其中,platform_ui 是一个指向 mj::GlfwAdapter 的指针, 它的基类 PlatformUIAdapter 是一个面向各类 UI 的接口, 如果我们不想 GLFW 完全可以基于该接口封装一个其它的图形界面。cam 和 opt 已经在编程套路中介绍过了, 主要用于图形渲染。pert 主要用于鼠标的交互。最后的布尔参数 is_passive 用于控制 Simulate 是否工作在 passive 模式下,在该模式下 Simulate 就不具有对 mjModel、mjData 以及各类 mjv 对象的独占访问权限。
Simulate::Simulate(std::unique_ptr<PlatformUIAdapter> platform_ui, // std::make_unique<mj::GlfwAdapter>()
mjvCamera* cam, // 用于图形渲染的相机
mjvOption* opt, // 可视化选项
mjvPerturb* pert, // 关于鼠标操作的数据结构
bool is_passive /* = false */) // Simulate 是否工作在 passive 模式下
接下来对部分成员变量进行初始化。其成员的构造列表中,除了与输入参数一一对应的赋值之外,还多了一个 uistate 的初始赋值的工作。 uistate 是在 mujoco 开放的头文件 mjui.h中定义的类 mjuiState 的对象。 该对象用于维护鼠标和键盘的交互状态,其中还特别提供了字段 dropcount 和 droppaths 用于记录拖拽的文件路径。
: is_passive_(is_passive), cam(*cam), opt(*opt), pert(*pert),
platform_ui(std::move(platform_ui)), uistate(this->platform_ui->state())
在构造函数体中,完成了定义在mjvisualize.h中的类 mjvScene 和类 mjvSceneState 对象的初始化操作。 mjvScene 是主要用于 OpenGL 的渲染,而 mjvSceneState 主要记录的是 mjModel 和 mjData 对象中用于重新渲染场景的必要字段。
{
mjv_defaultScene(&scn);
mjv_defaultSceneState(&scnstate_);
}
2. RenderLoop()
在main() 函数的最后通过 sim->RenderLoop();
开启了UI交互和图形渲染的超级循环。
与仿真线程类似,该函数大体上可以分为三段:先完成一堆初始化的工作,然后在一个 while 循环中不断的检查UI状态完成渲染直到满足退出条件,最后释放一些对象资源。
2.1 初始化
void Simulate::RenderLoop() {
mjcb_time = Timer;
// init abstract visualization
mjv_defaultCamera(&this->cam);
mjv_defaultOption(&this->opt);
InitializeProfiler(this);
InitializeSensor(this);
如左侧的代码片段所示,RenderLoop() 在一开始先注册了一个计时函数。mjcb_time
是一个定义在
engine_callback.h 中的函数指针。
如下图所示,函数 Timer() 返回的是,单位为毫秒单调递增的时间戳 std::chrono::steady_clock::now,主要给内置的 Profiler 绘制曲线提供时间参考。
上面的代码片段,接下来重置了用于图形渲染的相机对象和可视化选项。同时通过两个 InitializeXXXXXX 的函数完成了 Profiler 和 Sensor 窗口的初始化。 如右图中红色标记所示,点选 Profiler 按键可以打开或者关闭该窗口,它主要是绘制一些统计信息的曲线。黄色标记则对应 Sensor 窗口, 看字面意思应该是传感器数据的曲线。
if (!is_passive_) {
mjv_defaultScene(&this->scn);
mjv_makeScene(nullptr, &this->scn, kMaxGeom);
}
if (!this->platform_ui->IsGPUAccelerated()) {
this->scn.flags[mjRND_SHADOW] = 0;
this->scn.flags[mjRND_REFLECTION] = 0;
}
如左侧的代码片段所示,按照编程套路完成了场景对象的初始化。这个 is_passive_ 在 main() 函数中构造simulate的时候就已经是 false 了, 没太理解这个 Passive 存在的意义是啥。看字面意思,如果检查到图形界面没有 GPU 加速的功能,就不开启阴影和反光效果的渲染特性。
// 省略窗口元素和样式相关的代码
this->platform_ui->SetEventCallback(UiEvent);
this->platform_ui->SetLayoutCallback(UiLayout);
// 省略了好多代码,初始化结束了
接下来的有一段比较长的代码它主要是在定义各个窗口元素和它们的样式。比较重要的是左面代码片段中抄下来的那两行,它们注册了 UI 的事件响应函数和元素排版函数。 Simulate 的交互状态基本是通过这两个函数维护的。
2.2 while 循环
图形界面的交互主要就是在处理各种各样的鼠标和键盘的事件,而这些事件的发生完全事随机的。 这与我们在Linux下的事件与网络编程中遇到的问题一样,可以通过反射(reactor)模式来解决。 大体的套路就是,针对各类事件定义一系列的回调函数,然后在超级循环中不断地检查是否事件发生,然后根据发生的事件调用对应的回调函数。 下面是这个超级循环的代码片段,它在不断地检查是否需要关闭窗口或者有退出请求。
while (!this->platform_ui->ShouldCloseWindow() && !this->exitrequest.load()) {
由于这一段工作与仿真线程存在竞争问题,所以一开始先对成员互斥量 mtx 加锁,来完成系统状态的更新。这个 mtx 是一个 std::recursive_mutex 类型的可重入的信号量,在同一个线程中可以重复对它加锁。
{
const MutexLock lock(this->mtx);
// load model (not on first pass, to show "loading" label)
if (this-&loadrequest == 1)
this->LoadOnRenderThread();
else if (this->loadrequest == 2)
this->loadrequest = 1;
// poll and handle events
this->platform_ui->PollEvents();
// upload assets if requested
bool upload_notify = false;
if (hfield_upload_ != -1) {
mjr_uploadHField(m_, &platform_ui->mjr_context(), hfield_upload_);
hfield_upload_ = -1;
upload_notify = true;
}
if (mesh_upload_ != -1) {
mjr_uploadMesh(m_, &platform_ui->mjr_context(), mesh_upload_);
mesh_upload_ = -1;
upload_notify = true;
}
if (texture_upload_ != -1) {
mjr_uploadTexture(m_, &platform_ui->mjr_context(), texture_upload_);
texture_upload_ = -1;
upload_notify = true;
}
if (upload_notify)
cond_upload_.notify_all();
// update scene, doing a full sync if in fully managed mode
if (!this->is_passive_) {
Sync();
} else {
scnstate_.data.warning[mjWARN_VGEOMFULL].number += mjv_updateSceneFromState(
&scnstate_, &this->opt, &this->pert, &this->cam, mjCAT_ALL, &this->scn);
}
}
上面这段加锁的语句中,调用了两个比较重要的函数 this->platform_ui->PollEvents()
和 Sync()
。
接下来在超级循环中,调用函数 Render() 完成渲染,并统计一些时间信息用更新帧率。
// render while simulation is running
this->Render();
// 省略统计信息相关语句
}
2.3 释放资源
资源的释放没什么特别需要注意的。
const MutexLock lock(this->mtx);
mjv_freeScene(&this->scn);
if (is_passive_)
mjv_freeSceneState(&scnstate_);
this->exitrequest.store(2);
}
3. 执行器的交互
从官方视频中可以看到这个 simulation 的交互功能还挺多的。 但其实我们并不关心这些功能是怎么实现的,我只想知道应该修改什么数据让这个四足机器人动起来。 我把模型加载进来后,注意到在开启仿真模式(左侧边栏 Run)下,可以通过右侧边栏的 Control 修改机器人的状态。我们来分析一下这个过程,摸一下 mujoco 的执行器机制。
如果没有加载模型,那么右侧边栏就是空的。simulation 在加载模型的时候,会调用函数 MakeControlSection,根据模型文件中的 actuator
标签构建右侧的 control 边栏。
如下面的代码片段所示,关键就是在 for 循环中保留的那几句。在 for 循环中遍历各个actuator的标签,直接将对应的 mjData 的 ctrl 字段的地址注册到 UI 控件上。这样 UI 控件的数值发生了改变,
就会直接修改到目标执行器的控制量上。
void MakeControlSection(mj::Simulate* sim, int oldstate) {
// 省略准备的语句
for (int i=0; i < sim->actuator_ctrlrange_.size() && itemcnt<mjMAXUIITEM; i++) {
// 省略了很多,只保留了关键的这几句
if (!sim->is_passive_) {
defSlider[0].pdata = &sim->d_->ctrl[i];
} else {
defSlider[0].pdata = &sim->ctrl_[i];
} } }
根据官方文档的介绍,在 MuJoCo 中,
所有的执行器都是单输入单输出的(Single-Input-Single-Output, SISO)。对于一个执行器 \(i\),其输入是由 mjData.ctrl
保存的一个标量,
一般用符号 \(u_i\) 表示控制量。输出也是一个标量用符号 \(p_i\) 表示,描述的是转换到关节空间后的作用力,保存在 mjData.actuator_force
。
所以上面代码片段中,直接对 mjData 的 ctrl 字段的修改就可以通过交互的方式把输入用户需要的控制量。
如右图所示,模型中一共定义了12个执行器, 其中,属性 name 给每个执行器定义了一个唯一的名字,我们可以据此区分不同的执行器对象。class 对应着 default 标签中的一个默认配置项, 详细参见初识仿真系统模型。它定义了各类执行器的运行参数。 最后的 joint 或者 tendon 属性则表示该执行器对应着模型中的哪个关节或者肌腱对象。
左图是三类控制器的默认参数配置项,default 标签的定义,它们只有控制的限幅不同,其他的设置都与第一行中的 general 标签保持一致。
通过属性 dyntype 开启了 mujoco 的激励动力学(activation dynamics)的特性,引入了一个内部的状态(internal state)\(w_i\),由 mjData.act
保存。
这里选用的是 filter 的激励动力学,根据MJCF的定义,其表达式为:
act_dot = (ctrl - act) / dynprm[0]
。其中 act_dot 是激励状态的一阶导数,ctrl 是用户的控制量\(u_i\),act是mjData.act
保存的激励状态\(w_i\),
dynprm 就是 general 标签的最后一个属性。
从激励状态到控制器输出的力,还需要经过函数 \(p_i\left(u_i, w_i, l_i, \dot{l}_i\right)\),这里的通过 biastype, biasprm, gainprm 定义了该函数的形式为: $$ p_i = a w_i + b_0 + b_1 l_i + b_2 \dot{l}_i $$ 其中,\(a\)对应 gainprm 为增益参数,\(b_0, b_1, b_2\) 对应参数 biasprm,\(w_i\)是执行器的激励状态,\(l_i\)是执行器的长度。