在本教程中,我们将从头构建传送带(或卡特彼勒,在这种情况下可以查看本教程的最后部分)。下图说明了我们将设计的模拟场景:
我们将建造一条传动带,其行为应与真实传送带完全相同,每个传送带垫都是动态单独模拟的。这意味着较小的物体可能被困在两个相邻的垫之间。这种类型的模拟可能是计算密集型的,并且会减慢整个模拟过程。有一种替代的,简化的方法来模拟传送带,这也将在本教程中进行解释,并清楚地标记为方法 B(与模拟单个垫的方法 A 相反)。
首先,重新开始 V-REP。上图中的传送带基本上由沿其轨迹驱动若干垫的路径对象构成。使用 [Popup menu --> Add --> Path --> Circle type] 添加圆形路径。要从上面查看路径,将视图切换到第 6 页。使用适合视图工具栏按钮使相机更近:
选择路径对象后,请注意路径是如何由蓝点定义的,其间执行贝塞尔插值。你还可以区分红色球体,它表示路径位置,它不是路径的位置,而是沿路径的位置。
在将垫子连接到路径之前,让我们准备路径的正确大小和形状。您可以导入路径,也可以修改和编辑现有路径,我们将选择第二种方法。选择路径后,单击路径编辑模式工具栏按钮进入路径编辑模式:
我们现在处于路径编辑模式。我们想设计一条 10 厘米厚,20 厘米宽,1 米长的传送带。构成皮带的各个衬垫厚度为 5 毫米
在路径编辑模式对话框中,点击 Path is flat 和 Path is flat。选择所有路径点,然后打开位置对话框,在 position scaling 选项卡上,在右侧输入 3 倍缩放系数 0.19,然后单击 Scale position。这只是恰当地缩放了路径。使用鼠标滚轮,靠近路径。选择最上面的路径点。用 ctrl-c 复制它。然后再次选择它并使用 ctrl-v 将缓冲区粘贴到所选位置之后。我们刚创建了一个与最上面的路径点重合的路径点:我们复制了路径点 #13,然后粘贴了它的副本。新路径点是路径点 #14,如下图所示:
现在用最下面的路径点重复相同的过程。现在我们有两个中间路径点重复,我们可以拉伸路径,即将左右部分分开:在场景层次中选择路径点 #6 到路径点 #14,并在位置对话框的转换选项卡上,对于 Along X,输入 -0.5,然后单击 X-translate selection。现在缩小一点。这是你应该拥有的:
现在选择左侧路径点,并以相似的方式将它们向正 x 坐标移动 0.5 米。路径准备好了:
退出路径编辑模式,选择路径并在主窗口的信息文本部分注意“最后选择的对象类型:路径”(贝塞尔曲线点数 = 270,总长度 = 2.2985,p = + 0.0000,Vn = + 0.0000)”。这告诉我们路径的长度是 2.2985 米。我们现在可以计算出我们想要多少个垫,它们的宽度以及垫间距离应该是多少。我们使用 40 个垫,宽度为 5 厘米,这导致垫间距为 0.75 厘米
单击 [Popup menu --> Add --> Primitive shape --> Cuboid]。将出现基本形状对话框,允许您调整各种参数。在 x-, y-, and z-sizes 中输入(0.05; 0.005; 0.18)。
方法A.
只需单击确定。这增加了一个动态且可响应场景的纯形状。视图切换到第 1 页。现在您可以看到添加的形状。将其重命名为 “pad0”(您可以通过在场景层次结构中双击其名称来重命名任何对象)。使用位置对话框,将垫子的绝对 z 坐标设置为0。双击场景层次结构中的垫子图标以打开形状属性对话框。调整其颜色(单击 Adjust outside color )。然后,在形状动态属性对话框中,选中 Static ,以便在模拟过程中垫不会掉落。在对象公共属性中,检查以下项目:Select base of model instead,Colliable,Measurable,Renderable 和 Detectable properties。在 Visibility layers 部分中,还启用第 9 层(但也保持第 1 层也启用)。
方法B.
取消选中 Create dynamic and respondable shape,然后单击 Ok。这会为场景添加一个静态的纯形状。视图切换到第1页。现在您可以看到添加的形状。将其重命名为“pad0”(您可以通过在场景层次结构中双击其名称来重命名任何对象)。使用位置对话框,将垫子的绝对 z 坐标设置为 0。双击场景层次结构中的垫子图标以打开形状属性对话框。整其颜色(单击 Adjust outside color )。在对象公共属性中,检查以下项目:Select base of model instead,Colliable,Measurable,Renderable 和 Detectable properties。在方法 B 中,传送带垫没有动态功能!
接下来,如果使用 sim.setPathPosition 修改路径的固有位置,我们希望将垫子附加到路径,以便它自动跟随路径的轨迹。对于这个任务,我们需要一个辅助对象:一个虚拟对象。单击 [Popup menu --> Add --> Dummy]。将虚拟对象重命名为“padLink0”。通过方向选项卡上的方向对话框将其方向调整为(0; -90; 0)。通过选择垫子,然后选择虚拟对象,然后单击 [Popup menu --> Edit --> Make last selected object parent] 将垫子连接到虚拟对象。接下来,以类似的方式将虚拟对象附加到路径(也可以通过在场景层次结构中拖放来实现父节点)。双击场景层次结构中的虚拟图标以打开虚拟属性对话框。检查 Follow parent path (only direct parent):注意虚拟对象和垫子刚刚跳到路径的红色球体的位置。选择虚拟对象不变,将复制增量项设置为“0.0575”。这表示如果复制虚拟对象,则其在路径上的偏移将自动增加 0.0575 米,即垫的宽度加上垫间距离。在对象公共属性对话框中,隐藏图层 11 中的虚拟对象(停用图层 3 并激活图层11)。
现在我们将添加剩余的39个垫。选择虚拟对象和垫子,然后使用 ctrl-c 复制选择。然后按 39 次 ctrl-v 将缓冲液准确粘贴 39 次。用 esc 键清除选择,然后在场景层次结构中选择 “padLink1” 到 “padLink39”(确保你没有选择垫子而只选择虚拟对象!),然后选择路径,然后单击 [Popup menu --> Edit --> Make last selected object parent]。这是你应该得到的:
下一步,我们将为传送带添加一个简化的外壳。添加尺寸为(0.12; 0.12; 0.2)的纯圆柱到场景中。将其 z 位置设为 0,将其 x 位置设置为 0.5,然后调整其颜色。复制并粘贴它,然后将副本移动到 x 坐标 -0.5 米。添加尺寸为(1.0; 0.09; 0.18)的纯立方体。将其 z 位置设为 0,并调整其颜色。选择两个柱面和刚刚添加的长方体,然后单击 [Popup menu --> Edit --> Grouping/Merging --> Group selected shapes]。将生成的形状重命名为“conveyorBelt”。在形状动力学属性对话框中,将“conveyorBelt”设为 static,并在对象公共属性中,选中Colliable,Measurable,Renderable 和 Detectable properties。同时按下 Visibility layer 图层按钮 9.然后将路径附加到 “conveyorBelt”。
方法B:
添加一个尺寸为(1.0; 0.1; 0.18)的纯长方体。将其 z 位置设置为 0.将生成的形状重命名为“conveyorForwarder”。在形状对话框中,将“conveyorForwarder”设为 static,并在对象公共属性对话框中将对象发送到 Visibility layer 9(禁用按钮 1 并启用按钮9)。然后将“conveyorForwarder”连接到“conveyorBelt”。 “ConveyorForwarder”是移动其他物体的对象,同时还有一个小技巧(见下文)。
现在绕绝对 x 轴将传送带主体旋转 90 度,并将其坐标设置为(0.0; 0.0; 0.5)。 选择路径,并在路径属性中取消选中 Show path line, Show orientation of points 和 Show current position on path。 选择“conveyorBelt”并在对象公共属性对话框中,选中 Object is model base。 单击 Edit model properties,然后在 Model content acknowledgments/Info 中,添加一些每次加载传送带模型时希望显示的文本。 最后从“conveyorBelt”开始折叠层次结构树。 我们的模型基本准备就绪:
请注意,单击传送带模型上的任何对象,将选择整个模型。 如果您希望选择单个对象,您仍然可以在场景层次结构中执行此操作,或者在单击对象时按住 shift 和 ctrl 键(两者同时!)。
路径的固有位置(因此,路径的移动)也可以通过 API 函数 sim.setPathPosition 进行修改。 在模型浏览器中查看其他传送带模型,了解如何执行此操作。
方法A.
选择“conveyorBelt”对象并单击 [Menu bar --> Add --> Associated child script --> Non threaded]。 这只是将非线程子脚本附加到模型底座上。 双击场景层次结构中的子脚本图标以打开子脚本。 用以下代码替换脚本:
function sysCall_init() pathHandle=sim.getObjectHandle("Path") sim.setPathTargetNominalVelocity(pathHandle,0) -- for backward compatibility end function sysCall_cleanup() end function sysCall_sensing() end function sysCall_actuation() beltVelocity=0.1 -- in meters/seconds local dt=sim.getSimulationTimeStep() local pos=sim.getPathPosition(pathHandle) pos=pos+beltVelocity*dt sim.setPathPosition(pathHandle,pos) -- update the path's intrinsic position end
以上代码有效地做了以下内容:在每次模拟过程中,修改路径的固有位置,以便产生传送带的固有运动。
方法B.选择“conveyorBelt”对象并单击 [Menu bar --> Add --> Associated child script --> Non threaded]。 这只是将非线程子脚本附加到模型库。 双击场景层次结构中的子脚本图标以打开子脚本。 用以下代码替换脚本:
function sysCall_init() pathHandle=sim.getObjectHandle("Path") forwarder=sim.getObjectHandle('conveyorForwarder') sim.setPathTargetNominalVelocity(pathHandle,0) -- for backward compatibility end function sysCall_cleanup() end function sysCall_sensing() end function sysCall_actuation() beltVelocity=0.1 -- in meters/seconds local dt=sim.getSimulationTimeStep() local pos=sim.getPathPosition(pathHandle) pos=pos+beltVelocity*dt sim.setPathPosition(pathHandle,pos) -- update the path's intrinsic position -- Here we "fake" the transportation pads with a single -- static cuboid that we dynamically reset at each -- simulation pass (while not forgetting to set its initial -- velocity vector) : local relativeLinearVelocity={-beltVelocity,0,0} -- Reset the dynamic cuboid from the simulation -- (it will be removed and added again): sim.resetDynamicObject(forwarder) -- Compute the absolute velocity vector: local m=sim.getObjectMatrix(forwarder,-1) m[4]=0 -- Make sure the translation component is discarded m[8]=0 -- Make sure the translation component is discarded m[12]=0 -- Make sure the translation component is discarded local absoluteLinearVelocity=sim.multiplyVector(m,relativeLinearVelocity) -- Now set the initial velocity of the dynamic cuboid: sim.setObjectFloatParameter(forwarder,3000,absoluteLinearVelocity[1]) sim.setObjectFloatParameter(forwarder,3001,absoluteLinearVelocity[2]) sim.setObjectFloatParameter(forwarder,3002,absoluteLinearVelocity[3]) end
以上代码有效地做了以下内容:在每次模拟过程中,修改路径的固有位置,以便产生传送带的固有运动。 同时,在每次模拟过程中,“conveyorForwarder”对象被“动态重置”(被移除然后再直接从动态模拟中添加到动态模拟中)和进行初始速度设置。 最初的速度会使其他物体在它上面移动! 这比单独模拟每个传送带垫的计算密集程度要低得多。
为了结束本教程,我们将保存刚刚创建的模型,以便它出现在 V-REP 的模型浏览器中。 选择模型,然后单击 [Menu bar --> File --> Save model as...]。 出现一个对话框,允许调整模型缩略图图像。 对缩略图图像满意后,单击确定并导航到 V-REP 的“模型/设备”文件夹并保存模型。
制作 caterpillar
in V-REP, caterpillars are simulated by using several dynamic cylinders along the caterpillar, to give the impression the caterpillar is moving the vehicle, when in fact, the cylinders are! This means that the caterpillar pads are just "eye candy", and dynamically not enabled (they should be static and non-respondable). The method of creating caterpillars is actually very similar to making a conveyor belt with METHOD B. Following figure illustrates the caterpillar concept in V-REP:
在V-REP中,通过使用沿着履带的几个动态气缸来模拟 caterpillar,以给出 caterpillar 正在移动车辆的印象,而实际上是气缸在做这个动作! 这意味着履带垫只是“障眼法”,动态不启用(它们应该是 static 和 non-respondable)。 创建 caterpillar 的方法实际上非常类似于使用方法 B 制作传送带。下图说明了 V-REP 中的 caterpillar 概念:
参考资料
1.V-REP官方文档:http://www.coppeliarobotics.com/helpFiles/