0. 软件安装
软件可以上面这个知乎的链接里看到,选择整合软体机器人插件版本下载:
最新的一般使用python3,如果开发环境使用的是python2,可以在下面选择合适的历史版本
开启软件:
下载已编译版本后,解压到常用软件目录。在Sofa_python3.8/bin中有一个runSofa文件。
如果是ubuntu系统,则在bin文件夹下打开终端,输入:
chmod a+x runSofa
./runSofa
可以启动软件。
或者右键runSofa文件选择属性,在权限勾选可执行文件,然后双击runSofa文件。
如果想为sofa创建图标,可以参考这篇链接: 为ubuntu添加图标
我在desktop文件中的代码展示在下面,以供参考:
注意Exec和Icon后面是我的软件安装目录,需要根据实际安装目录进行修改。
[Desktop Entry]
Name =SOFA
Exec =/home/zf/Software/Sofa_python3.8/bin/runSofa
Icon = /home/zf/Software/Sofa_python3.8/share/sofa/icons/MODELER.png
Encoding = UTF-8
Comment = SOFA
Terminal=false
Type=Application
StartupNotify=true
搞好之后在“显示应用程序”界面可以看到sofa图标
软件启动后默认展示一条蛇,点击左上角animate,蛇会掉下去,弹起来。
在file->open里可以打开其他工程。
在Windows版本里,解压缩后,在bin文件夹里双击runSofa.exe,可以运行软件。
比较推荐使用ubuntu版本,不知道为啥,我的Windows版本无法打开python文件写的工程。
外网看到有的解决方案是在edit->plugins manager里add SofaPython3.dll。试了下,没有用。
插播一条,最近我的Ubuntu版本也我无法打开python文件了,解决方案:打开sofa,edit->plugins manager,看列表里有没有sofaPython3,如果没有的话,点击下方的add按钮,在根目录下的lib文件夹或者plugins/sofaPython3/lib文件夹下选择libSofaPython3.so文件并确定添加。
同样的,如果plugins manager里没有softRobots等常用的插件,也可以到plugins里对应文件夹的lib里找so文件。
1. 配置Pycharm
这部分写的方法并不地道,更好的方法可以到我的 sofa学习笔记(四)里看看
在写sofa的文件时,想在pycharm里编写,企图在引用其plugin里的API后实现代码提示。
尝试了以下方法,不一定是正确的做法,但是Pycharm里import不出错,且可以提示大部分代码了。
1.1在pycharm里配置
在pycharm里找到:文件=>设置=> 项目=> 项目结构=> 点击右边的 “添加内容根”=> 分别添加以下内容根目录:
- Sofa_python3.8/plugins/STLIB/lib/python3/site-packages
- Sofa_python3.8/plugins/SoftRobots/lib/python3/site-packages
- Sofa_python3.8/plugins/SofaPython3/lib/python3/site-packages
其中 Sofa_python3.8是Sofa的安装路径。
1.2 将包添加到python目录中
如果嫌麻烦,可以将这些包手动添加到常用的python目录中,具体操作为:
- 将上述目录的site-packages文件夹里的内容都复制到python对应的位置:
我使用了anaconda,环境名称为py38,对应的位置为的位置是:
/home/zf/anaconda3/envs/py38/lib/python3.8/site-packages
这个地址中的/home/zf/anaconda3应该替换为实际的anaconda安装位置,py38应该替换为实际的python环境名称。此时,pycharm中能够进行一些代码提示,但是仍然无法运行,会报错显示一些so文件找不到,此时可以将下面几个目录中的so文件复制到/home/zf/anaconda3/envs/py38/lib文件中:
Sofa_python3.8/plugins/STLIB/lib
Sofa_python3.8/plugins/SoftRobots/lib
Sofa_python3.8/plugins/SofaPython3/lib如果使用的是anaconda的默认base环境(我这里的base是python3.9),则上面这段里提到的
/home/zf/anaconda3/envs/py38/lib/python3.8/site-packages应该改为:
/home/zf/anaconda3/lib/python3.9/site-packages;
/home/zf/anaconda3/envs/py38/lib应该改为:
/home/zf/anaconda3/lib;如果使用的是系统python,没找到位置,如果有知道的麻烦告知,感谢!
至此,可以勉强在pycharm里进行开发了。但是因为官方实例给的比较多,不用完全白手起家地去写代码,在文本编辑器里从各个实例里复制粘贴也能满足日常使用需求。这里费这么大劲配置pycharm主要是想让自己舒服,或许有一丝丝可能方便后面白手起家(以及在ROS环境中使用)。
2. 跟做实例
实例可以在以下路径中找到:
Sofa_python3.8/plugins/SoftRobots/docs/sofapython3/tutorials
2.0 一些软件操作小tips
坐标系
这个坐标轴顺序是:XYZ->RGB
在界面上同时按下 Ctrl+shift+R, 可以显示物体的连体坐标系。
背景
按shift+B,可以切换背景(记忆方法:shift background, 改变背景)
隐藏/显示某些零件
在树形图里找到零件,右键选 deactivate(反激活),要激活可以右键点 activate
注:不知道怎么能在软件中操作仅仅让零件不可见,如有好方法,欢迎补充。
在脚本里,可以编辑模型的color:color=[1.0,0.0,0.0,1.0],第四个参数表示透明度。
隐藏/显示某类物体
在左边树形图上方点击 view, 在里面可以选择显示隐藏哪些类别的模型,比如可以只显示外观模型而不显示网格模型,或者只显示法向量等。
2.1 FirstSteps
建议从First steps开始跟做,在软件中打开下图中的python 文件,会跳出一个文档图文教程,点击教程里的蓝字Try the scene in Sofa.可以看到当前步骤的效果,
右键软件root下面随便哪个文件,选择弹出来的菜单里的open file in editor, 可以看到当前正在显示的工程的代码,修改代码后可以在file里选reload进行刷新。
这个实例内容比较简单,原教程也比较详细,B站上能搜到视频(英文),就不跟做了。
本篇主要跟做CableGripper。
2.2 CableGripper
工程位置:Sofa_python3.8/plugins/SoftRobots/docs/sofapython3/tutorials/CableGripper
这个工程是仿真一个线驱动软体夹爪,工程实现的效果为可以控制夹爪上下和开闭,以抓取物体,如下图所示:
在sofa软件里打开cablegripper-tuto.py,会弹出图文教程,下面将基于教程跟做这个工程,并适当查漏补缺。
2.2.1 新建项目
在开始之前曾经怀疑过这个功能包都在sofa安装目录下,没有直接安装到python中的情况下,是不是只能将项目新建到sofa的这个教程的文件夹下,经过实测,不是。项目可以新建到任意位置。
项目的结构可以参考实例里的“myproject”文件夹,这个文件夹里就是完整的项目,外面的“details”“images”是用来写它的图文教程的,与项目本身无关。
- 首先新建一个项目文件夹,名字随便取,我这里叫sofa_test。为了使项目更整洁,在项目文件夹下新建一个用来放模型和其他素材的文件夹,这里和实例一样新建“data”,在data下新建“mesh”。
- “myproject”文件夹中的几个python文件中,cablegripper.py是主文件,因此可以先创建这个python文件。其他文件将在后面跟做实例时创建。
2.2.2 创建场景
图文教程里的step 1.
创建一个很简单的场景,包含了一个地面和一个立方体,代码如下:
# -*- coding: utf-8 -*-
from stlib3.physics.rigid import Floor
from stlib3.physics.rigid import Cube
def createScene(rootNode):
# 新建根节点,并定义可见属性
rootNode.addObject('VisualStyle', displayFlags = "showBehavior showCollisionModels")
# 定义地面,放在根节点下
Floor(rootNode,
translation=[0.0,-160.0,0.0], # 相对于世界坐标系远点做平移
isAStaticObject=True) # 固定物体
# 定义立方体,放在根节点下
Cube(rootNode,
translation=[0.0,0.0,0.0], # 初始位置,在世界坐标系原点;Cube这个类是从扩展库里直接调用的。
uniformScale=20, # 这个不知道是在定义啥玩意,边长?
color=[1.0,0.0,0.0,1.0]) # 定义颜色,红绿蓝和透明度。
# 注意编辑完颜色后在软件里reload后,软件中是模型和碰撞模型一起显示的,
# 要看模型颜色,可以在左下角框里的 view, 只勾选visual models
return rootNode
# -*- coding: utf-8 -*-
from stlib3.physics.rigid import Floor
from stlib3.physics.rigid import Cube
def createScene(rootNode):
# 新建根节点,并定义可见属性
rootNode.addObject('VisualStyle', displayFlags = "showBehavior showCollisionModels")
# 定义地面,放在根节点下
Floor(rootNode,
translation=[0.0,-160.0,0.0], # 相对于世界坐标系远点做平移
isAStaticObject=True) # 固定物体
# 定义立方体,放在根节点下
Cube(rootNode,
translation=[0.0,0.0,0.0], # 初始位置,在世界坐标系原点;Cube这个类是从扩展库里直接调用的。
uniformScale=20, # 这个不知道是在定义啥玩意,边长?
color=[1.0,0.0,0.0,1.0]) # 定义颜色,红绿蓝和透明度。
# 注意编辑完颜色后在软件里reload后,软件中是模型和碰撞模型一起显示的,
# 要看模型颜色,可以在左下角框里的 view, 只勾选visual models
return rootNode
写完后可以在软件中open,点animate,立方体会掉下去(因为这里还没引入碰撞属性)
2.2.3 手指建模
图文教程里的step 2.
这一步要创建一个 手指函数,调用了弹性材料对象。这里先放代码,后说明其中调用的模型文件的生成方法。
# -*- coding: utf-8 -*-
from stlib3.physics.deformable import ElasticMaterialObject
from stlib3.physics.constraints import FixedBox
# 定义手指函数,方便后面写手爪的代码时直接调用。
# 函数的参数里都写了默认值,在调用时可以重新赋值
def Finger(parentNode=None, name="Finger",
rotation=[0.0, 0.0, 105.0], translation=[0.0, 0.0, 0.0],
fixingBox=[0.0, 0.0, 0.0], pullPointLocation=[0.0, 0.0, 0.0]):
finger = parentNode.addChild("Finger") # 定义子节点finger
eobject = ElasticMaterialObject(finger,
volumeMeshFileName="data/mesh/finger.vtk",
poissonRatio=0.3,
youngModulus=18000,
totalMass=0.5,
surfaceColor=[0.2, 0.5, 0.7, 1],
surfaceMeshFileName="data/mesh/finger.stl",
rotation=rotation,
translation=translation)
# 上面volumeMeshFileName传入网格模型文件
# surfaceMeshFileName引入外观模型文件
# poissonRatio泊松比;youngModulus杨氏模量;totalMass总质量
# rotation,translation 位姿变换
finger.addChild(eobject) # 将读入的弹性手指模型添加为finger的子节点
# 有了这个固定框,手指就固定了,开始仿真时不会下坠或被拖动旋转
FixedBox(eobject,
doVisualization=True,
atPositions=[-10, -10, -10, 10, 10, 10])
# 这个函数大概是为了单独运行这个文件时显示手指用的,后面集成成爪子时就不调用它了
def createScene(rootNode):
# -*- coding: utf-8 -*-
from stlib3.scene import MainHeader
MainHeader(rootNode, plugins=["SoftRobots"])
rootNode.VisualStyle.displayFlags = 'showForceFields showBehaviorModels showInteractionForceFields'
Finger(rootNode)
return rootNode
# -*- coding: utf-8 -*-
from stlib3.physics.deformable import ElasticMaterialObject
from stlib3.physics.constraints import FixedBox
# 定义手指函数,方便后面写手爪的代码时直接调用。
# 函数的参数里都写了默认值,在调用时可以重新赋值
def Finger(parentNode=None, name="Finger",
rotation=[0.0, 0.0, 105.0], translation=[0.0, 0.0, 0.0],
fixingBox=[0.0, 0.0, 0.0], pullPointLocation=[0.0, 0.0, 0.0]):
finger = parentNode.addChild("Finger") # 定义子节点finger
eobject = ElasticMaterialObject(finger,
volumeMeshFileName="data/mesh/finger.vtk",
poissonRatio=0.3,
youngModulus=18000,
totalMass=0.5,
surfaceColor=[0.2, 0.5, 0.7, 1],
surfaceMeshFileName="data/mesh/finger.stl",
rotation=rotation,
translation=translation)
# 上面volumeMeshFileName传入网格模型文件
# surfaceMeshFileName引入外观模型文件
# poissonRatio泊松比;youngModulus杨氏模量;totalMass总质量
# rotation,translation 位姿变换
finger.addChild(eobject) # 将读入的弹性手指模型添加为finger的子节点
# 有了这个固定框,手指就固定了,开始仿真时不会下坠或被拖动旋转
FixedBox(eobject,
doVisualization=True,
atPositions=[-10, -10, -10, 10, 10, 10])
# 这个函数大概是为了单独运行这个文件时显示手指用的,后面集成成爪子时就不调用它了
def createScene(rootNode):
# -*- coding: utf-8 -*-
from stlib3.scene import MainHeader
MainHeader(rootNode, plugins=["SoftRobots"])
rootNode.VisualStyle.displayFlags = 'showForceFields showBehaviorModels showInteractionForceFields'
Finger(rootNode)
return rootNode
这一步代码比较简单,比较麻烦的生成弹性手指需要的俩模型,这需要从其他软件生成。
官方推荐的软件是Gmsh。
在已经有了模型的step文件的情况下使用Gmsh生成stl和vtk文件。 step模型文件可以由CAD、Solidworks等三维软件生成。
Gmsh的使用可以看我的另一篇学习笔记:,笔记比较长,可以只看“软件操作”部分。网格画出来后分别在file里export为stl和vtk格式。
注:我最初使用Solidworks生成stl文件,结果在导入sofa后无法与vtk网格文件绑定,运动时不能随动,后来改用gmsh导出stl文件就解决了这个问题。估计是不同软件编码有些微差别。
2.2.4 线驱手指
图文教程里的step 3
接下来添加手指的驱动方式,使用的是线驱,即拉动埋在手指中的非弹性的线缆,使手指弯曲。
线缆使用json文件定义,文件名为cable.json,存放在下面这个目录:
Sofa_python3.8/plugins/SoftRobots/docs/sofapython3/tutorials/CableGripper/myproject/data/mesh
文件内容为:
[[-17.5, 12.5, 2.5],
[-32.5, 12.5, 2.5],
[-47.5, 12.5, 2.5],
[-62.5, 12.5, 2.5],
[-77.5, 12.5, 2.5],
[-83.5, 12.5, 4.5],
[-85.5, 12.5, 6.5],
[-85.5, 12.5, 8.5],
[-83.5, 12.5, 10.5],
[-77.5, 12.5, 12.5],
[-62.5, 12.5, 12.5],
[-47.5, 12.5, 12.5],
[-32.5, 12.5, 12.5],
[-17.5, 12.5, 12.5]]
注:这个文件在文本编辑器里把点的坐标按格式输入进去然后把后缀改为.json就行。线缆的图像为:
有了JSON文件后,开始编写调用线缆的代码
图文教程里的线缆函数和实例里实际使用的代码略有不同,这里以实例为准:
from stlib3.physics.deformable import ElasticMaterialObject # 引入可变形弹性体
from stlib3.physics.constraints import FixedBox # 引入固定框
# -*- coding: utf-8 -*-
from softrobots.actuators import PullingCable # 引入牵引线缆的包
from splib3.loaders import loadPointListFromFile #引入加载点的包
import Sofa.Core # sofa的核,在初始化时有用
import Sofa.constants.Key as Key # 引入sofa读取键盘的包
# 定义手指控制器的类
# 继承父类Sofa.Core.Controller
class FingerController(Sofa.Core.Controller):
def __init__(self, *args, **kwargs): # 初始化
Sofa.Core.Controller.__init__(self, args, kwargs) # 初始化父类
self.cable = args[0]
self.name = "FingerController"
def onKeypressedEvent(self, e): # 添加键盘控制
displacement = self.cable.CableConstraint.value[0]
if e["key"] == Key.plus:
displacement += 1.
elif e["key"] == Key.minus:
displacement -= 1.
if displacement < 0:
displacement = 0
self.cable.CableConstraint.value = [displacement]
def Finger(parentNode=None, name="Finger",
rotation=[0.0, 0.0, 0.0], translation=[0.0, 0.0, 0.0],
fixingBox=[0.0, 0.0, 0.0], pullPointLocation=[0.0, 0.0, 0.0]):
finger = parentNode.addChild(name)
eobject = ElasticMaterialObject(finger, volumeMeshFileName="data/mesh/finger.vtk")
finger.addChild(eobject)
FixedBox(eobject, doVisualization=True, atPositions=[-10, -10, -10, 10, 10, 10])
cable = PullingCable(eobject, cableGeometry=loadPointListFromFile("data/mesh/cable.json"))
# 调用,大概addObject有自行解析这个类的方法。
finger.addObject(FingerController(cable))
def createScene(rootNode):
# -*- coding: utf-8 -*-
from stlib3.scene import MainHeader
MainHeader(rootNode, plugins=["SoftRobots"])
rootNode.VisualStyle.displayFlags = "showBehavior showCollisionModels"
# 自由运动动画循环
rootNode.addObject('FreeMotionAnimationLoop')
# 通用约束求解器
rootNode.addObject('GenericConstraintSolver', tolerance=1e-5, maxIterations=100)
Finger(rootNode)
return rootNode
from stlib3.physics.deformable import ElasticMaterialObject # 引入可变形弹性体
from stlib3.physics.constraints import FixedBox # 引入固定框
# -*- coding: utf-8 -*-
from softrobots.actuators import PullingCable # 引入牵引线缆的包
from splib3.loaders import loadPointListFromFile #引入加载点的包
import Sofa.Core # sofa的核,在初始化时有用
import Sofa.constants.Key as Key # 引入sofa读取键盘的包
# 定义手指控制器的类
# 继承父类Sofa.Core.Controller
class FingerController(Sofa.Core.Controller):
def __init__(self, *args, **kwargs): # 初始化
Sofa.Core.Controller.__init__(self, args, kwargs) # 初始化父类
self.cable = args[0]
self.name = "FingerController"
def onKeypressedEvent(self, e): # 添加键盘控制
displacement = self.cable.CableConstraint.value[0]
if e["key"] == Key.plus:
displacement += 1.
elif e["key"] == Key.minus:
displacement -= 1.
if displacement < 0:
displacement = 0
self.cable.CableConstraint.value = [displacement]
def Finger(parentNode=None, name="Finger",
rotation=[0.0, 0.0, 0.0], translation=[0.0, 0.0, 0.0],
fixingBox=[0.0, 0.0, 0.0], pullPointLocation=[0.0, 0.0, 0.0]):
finger = parentNode.addChild(name)
eobject = ElasticMaterialObject(finger, volumeMeshFileName="data/mesh/finger.vtk")
finger.addChild(eobject)
FixedBox(eobject, doVisualization=True, atPositions=[-10, -10, -10, 10, 10, 10])
cable = PullingCable(eobject, cableGeometry=loadPointListFromFile("data/mesh/cable.json"))
# 调用,大概addObject有自行解析这个类的方法。
finger.addObject(FingerController(cable))
def createScene(rootNode):
# -*- coding: utf-8 -*-
from stlib3.scene import MainHeader
MainHeader(rootNode, plugins=["SoftRobots"])
rootNode.VisualStyle.displayFlags = "showBehavior showCollisionModels"
# 自由运动动画循环
rootNode.addObject('FreeMotionAnimationLoop')
# 通用约束求解器
rootNode.addObject('GenericConstraintSolver', tolerance=1e-5, maxIterations=100)
Finger(rootNode)
return rootNode
放一个python小知识
在初始化类时的def __init__(self, *args, **kwargs),参数意义如下:
这个也不是什么重要的东西,但是python初学者会挠头。。。
在sofa里运行这个python文件,软件种场景的树形结构和线缆的参数如下图所示:
按照教程说的,运行场景后点一下模型后按住啊ctrl+"+",线缆会收缩,此时线缆的states里的位置速度加速度表格里的数值都会发生变化。
按照实例做的手指弯曲如下图所示:
我自己用的模型做的效果如下:
2.2.5 添加碰撞属性
图文教程 step 4.
默认情况下,Sofa不处理碰撞,因为它们的计算量很大。要激活碰撞,您需要特别定义检查collion的几何图形以及如何处理collion。这可以通过添加名为CollisionMesh的专用结构来实现。
默认情况下,不会处理物体的自碰撞,但如果对象是强变形的,则会导致一些不期望的情况,如下图所示:
这一步需要额外定义两个用于处理碰撞的图形,放在如下图所示的位置:
这一步的代码如下(越来越长了):
# -*- coding: utf-8 -*-
from stlib3.physics.deformable import ElasticMaterialObject
from stlib3.physics.constraints import FixedBox
from stlib3.physics.collision import CollisionMesh
from softrobots.actuators import PullingCable
from splib3.loaders import loadPointListFromFile
import Sofa.Core
import Sofa.constants.Key as Key
# 这个类的定义部分与前文一致
class FingerController(Sofa.Core.Controller):
def __init__(self, *args, **kwargs):
Sofa.Core.Controller.__init__(self, args, kwargs)
self.cable = args[0]
self.name = "FingerController"
def onKeypressedEvent(self, e):
displacement = self.cable.CableConstraint.value[0]
if e["key"] == Key.plus:
displacement += 1.
elif e["key"] == Key.minus:
displacement -= 1.
if displacement < 0:
displacement = 0
self.cable.CableConstraint.value = [displacement]
# 手指定义部分与前文有区别
def Finger(parentNode=None, name="Finger",
rotation=[0.0, 0.0, 0.0], translation=[0.0, 0.0, 0.0],
fixingBox=[0.0, 0.0, 0.0], pullPointLocation=[0.0, 0.0, 0.0]):
finger = parentNode.addChild(name)
eobject = ElasticMaterialObject(finger,
volumeMeshFileName="data/mesh/finger.vtk",
surfaceMeshFileName="data/mesh/finger.stl",
surfaceColor=[0.0, 0.7, 0.8]
)
finger.addChild(eobject)
FixedBox(eobject, doVisualization=True, atPositions=[-10, -10, -10, 10, 10, 10])
cable = PullingCable(eobject,
cableGeometry=loadPointListFromFile("data/mesh/cable.json"))
finger.addObject(FingerController(cable))
# 从这里开始添加碰撞属性
# 为手指本身添加碰撞属性
# collisionGroup=[1, 2]表示这个手指包含在1,2碰撞组里,(同组的结构不会碰撞)
CollisionMesh(eobject,
surfaceMeshFileName="data/mesh/finger.stl", name="part0",
collisionGroup=[1, 2])
# 为额外加入的贴片添加碰撞属性,放到1碰撞组
CollisionMesh(eobject,
surfaceMeshFileName="data/mesh/fingerCollision_part1.stl",
name="CollisionMeshAuto1", collisionGroup=[1])
# 为额外加入的贴片添加碰撞属性,放到2碰撞组
CollisionMesh(eobject,
surfaceMeshFileName="data/mesh/fingerCollision_part2.stl",
name="CollisionMeshAuto2", collisionGroup=[2])
# 经过以上操作,额外添加的两个贴片互相之间属于不同组,会发生碰撞。都不会与手指发生碰撞。
def createScene(rootNode):
# -*- coding: utf-8 -*-
from stlib3.scene import MainHeader, ContactHeader
MainHeader(rootNode, plugins=["SoftRobots"])
rootNode.VisualStyle.displayFlags = "showBehavior showCollisionModels"
# 设置碰撞属性
ContactHeader(rootNode, alarmDistance=4, contactDistance=3, frictionCoef=0.08)
Finger(rootNode)
return rootNode
# -*- coding: utf-8 -*-
from stlib3.physics.deformable import ElasticMaterialObject
from stlib3.physics.constraints import FixedBox
from stlib3.physics.collision import CollisionMesh
from softrobots.actuators import PullingCable
from splib3.loaders import loadPointListFromFile
import Sofa.Core
import Sofa.constants.Key as Key
# 这个类的定义部分与前文一致
class FingerController(Sofa.Core.Controller):
def __init__(self, *args, **kwargs):
Sofa.Core.Controller.__init__(self, args, kwargs)
self.cable = args[0]
self.name = "FingerController"
def onKeypressedEvent(self, e):
displacement = self.cable.CableConstraint.value[0]
if e["key"] == Key.plus:
displacement += 1.
elif e["key"] == Key.minus:
displacement -= 1.
if displacement < 0:
displacement = 0
self.cable.CableConstraint.value = [displacement]
# 手指定义部分与前文有区别
def Finger(parentNode=None, name="Finger",
rotation=[0.0, 0.0, 0.0], translation=[0.0, 0.0, 0.0],
fixingBox=[0.0, 0.0, 0.0], pullPointLocation=[0.0, 0.0, 0.0]):
finger = parentNode.addChild(name)
eobject = ElasticMaterialObject(finger,
volumeMeshFileName="data/mesh/finger.vtk",
surfaceMeshFileName="data/mesh/finger.stl",
surfaceColor=[0.0, 0.7, 0.8]
)
finger.addChild(eobject)
FixedBox(eobject, doVisualization=True, atPositions=[-10, -10, -10, 10, 10, 10])
cable = PullingCable(eobject,
cableGeometry=loadPointListFromFile("data/mesh/cable.json"))
finger.addObject(FingerController(cable))
# 从这里开始添加碰撞属性
# 为手指本身添加碰撞属性
# collisionGroup=[1, 2]表示这个手指包含在1,2碰撞组里,(同组的结构不会碰撞)
CollisionMesh(eobject,
surfaceMeshFileName="data/mesh/finger.stl", name="part0",
collisionGroup=[1, 2])
# 为额外加入的贴片添加碰撞属性,放到1碰撞组
CollisionMesh(eobject,
surfaceMeshFileName="data/mesh/fingerCollision_part1.stl",
name="CollisionMeshAuto1", collisionGroup=[1])
# 为额外加入的贴片添加碰撞属性,放到2碰撞组
CollisionMesh(eobject,
surfaceMeshFileName="data/mesh/fingerCollision_part2.stl",
name="CollisionMeshAuto2", collisionGroup=[2])
# 经过以上操作,额外添加的两个贴片互相之间属于不同组,会发生碰撞。都不会与手指发生碰撞。
def createScene(rootNode):
# -*- coding: utf-8 -*-
from stlib3.scene import MainHeader, ContactHeader
MainHeader(rootNode, plugins=["SoftRobots"])
rootNode.VisualStyle.displayFlags = "showBehavior showCollisionModels"
# 设置碰撞属性
ContactHeader(rootNode, alarmDistance=4, contactDistance=3, frictionCoef=0.08)
Finger(rootNode)
return rootNode
注:贴片最好在生成手指stl文件时顺便生成,实例中是使用VCG生成的,我是用Gmsh生成的,具体操作看我的另一篇学习笔记:
看“删除网格”部分,先生成模型的2D网格(即表面网格),然后删除不用的部分。
2.2.6 完整代码
图文教程step 6.
至此,线驱手指的核心部分已经搞定了,下面就是新建三个手指,组成爪子,实现抓取。该部分主要内容是将上面写的部件都放到一个主函数里。
爪子
首先是三个手指组成爪子的代码。
文件gripper.py。
# -*- coding: utf-8 -*-
from grippercontroller import GripperController
from finger import Finger
def Gripper(parentNode=None):
gripper = parentNode.addChild("Gripper")
f1 = Finger(gripper, "Finger1",
rotation=[0, 0, 105],
translation=[20.0, 0.0, 0.0],
fixingBox=[-20, -10, 0, 20, 10, 15],
pullPointLocation=[3, 10.5, 3])
f2 = Finger(gripper, "Finger2",
rotation=[180, 0, 65],
translation=[-10.0, 0.0, -4.0],
fixingBox=[-20, -10, -30, 20, 10, 0],
pullPointLocation=[3, 10.5, -7])
f3 = Finger(gripper, "Finger3",
rotation=[180, 0, 65],
translation=[-10.0, 0.0, 34.0],
fixingBox=[-20, -10, 0, 20, 10, 50],
pullPointLocation=[3, 10.5, 31.5])
gripper.addObject(GripperController([f1, f2, f3]))
return gripper
def createScene(rootNode):
"""To test the content of this file, try:
>>> runSofa gripper.py
"""
from stlib3.scene import MainHeader, ContactHeader
MainHeader(rootNode, gravity=[0.0, -981.0, 0.0], plugins=["SoftRobots"])
ContactHeader(rootNode, alarmDistance=4, contactDistance=3, frictionCoef=0.08)
rootNode.VisualStyle.displayFlags = "showBehavior showCollisionModels"
Gripper(rootNode)
return rootNode
# -*- coding: utf-8 -*-
from grippercontroller import GripperController
from finger import Finger
def Gripper(parentNode=None):
gripper = parentNode.addChild("Gripper")
f1 = Finger(gripper, "Finger1",
rotation=[0, 0, 105],
translation=[20.0, 0.0, 0.0],
fixingBox=[-20, -10, 0, 20, 10, 15],
pullPointLocation=[3, 10.5, 3])
f2 = Finger(gripper, "Finger2",
rotation=[180, 0, 65],
translation=[-10.0, 0.0, -4.0],
fixingBox=[-20, -10, -30, 20, 10, 0],
pullPointLocation=[3, 10.5, -7])
f3 = Finger(gripper, "Finger3",
rotation=[180, 0, 65],
translation=[-10.0, 0.0, 34.0],
fixingBox=[-20, -10, 0, 20, 10, 50],
pullPointLocation=[3, 10.5, 31.5])
gripper.addObject(GripperController([f1, f2, f3]))
return gripper
def createScene(rootNode):
"""To test the content of this file, try:
>>> runSofa gripper.py
"""
from stlib3.scene import MainHeader, ContactHeader
MainHeader(rootNode, gravity=[0.0, -981.0, 0.0], plugins=["SoftRobots"])
ContactHeader(rootNode, alarmDistance=4, contactDistance=3, frictionCoef=0.08)
rootNode.VisualStyle.displayFlags = "showBehavior showCollisionModels"
Gripper(rootNode)
return rootNode
爪子控制器
grippercontroller.py
需要注意的是,在GripperController.py 里还是有一些门道的,涉及到坐标变换,这里不多说了,要是搞不清楚可以分别定义三根手指头,虽然麻烦些,但总归能实现。
# -*- coding: utf-8 -*-
import Sofa.Core
import Sofa.constants.Key as Key
def getTranslated(points, vec):
r=[]
for v in points:
r.append( [v[0]+vec[0], v[1]+vec[1], v[2]+vec[2]] )
return r
class GripperController(Sofa.Core.Controller):
def __init__(self, *args, **kwargs):
Sofa.Core.Controller.__init__(self,args,kwargs)
self.fingers = args[0]
self.name = "GripperController"
def onKeypressedEvent(self,e):
direction = None
if e["key"]==Key.uparrow:
direction = [0.0, 1.0, 0.0]
elif e["key"]==Key.downarrow:
direction = [0.0, -1.0, 0.0]
elif e["key"]==Key.leftarrow:
direction = [1.0, 0.0, 0.0]
elif e["key"]==Key.rightarrow:
direction = [-1.0, 0.0, 0.0]
if direction is not None and self.fingers is not None:
for finger in self.fingers:
m = finger.getChild("ElasticMaterialObject")
mecaobject = m.getObject("dofs")
mecaobject.findData('rest_position').value = getTranslated(mecaobject.rest_position.value, direction)
cable = m.getChild("PullingCable").getObject("CableConstraint")
p = cable.pullPoint.value
cable.findData("pullPoint").value = [p[0] + direction[0], p[1] + direction[1], p[2] + direction[2]]
def createScene(rootNode):
rootNode.addObject(GripperController(None))
return
# -*- coding: utf-8 -*-
import Sofa.Core
import Sofa.constants.Key as Key
def getTranslated(points, vec):
r=[]
for v in points:
r.append( [v[0]+vec[0], v[1]+vec[1], v[2]+vec[2]] )
return r
class GripperController(Sofa.Core.Controller):
def __init__(self, *args, **kwargs):
Sofa.Core.Controller.__init__(self,args,kwargs)
self.fingers = args[0]
self.name = "GripperController"
def onKeypressedEvent(self,e):
direction = None
if e["key"]==Key.uparrow:
direction = [0.0, 1.0, 0.0]
elif e["key"]==Key.downarrow:
direction = [0.0, -1.0, 0.0]
elif e["key"]==Key.leftarrow:
direction = [1.0, 0.0, 0.0]
elif e["key"]==Key.rightarrow:
direction = [-1.0, 0.0, 0.0]
if direction is not None and self.fingers is not None:
for finger in self.fingers:
m = finger.getChild("ElasticMaterialObject")
mecaobject = m.getObject("dofs")
mecaobject.findData('rest_position').value = getTranslated(mecaobject.rest_position.value, direction)
cable = m.getChild("PullingCable").getObject("CableConstraint")
p = cable.pullPoint.value
cable.findData("pullPoint").value = [p[0] + direction[0], p[1] + direction[1], p[2] + direction[2]]
def createScene(rootNode):
rootNode.addObject(GripperController(None))
return
主函数
# -*- coding: utf-8 -*-
from stlib3.scene import MainHeader, ContactHeader
from stlib3.physics.rigid import Floor, Cube
from gripper import Gripper
def createScene(rootNode):
"""This is my first scene"""
MainHeader(rootNode, gravity=[0.0, -981.0, 0.0], plugins=["SoftRobots"])
ContactHeader(rootNode, alarmDistance=4, contactDistance=3, frictionCoef=0.08)
rootNode.VisualStyle.displayFlags = "showBehavior showCollisionModels"
Gripper(rootNode)
Floor(rootNode,
color=[1.0, 0.0, 0.0, 1.0],
translation=[0.0, -160.0, 0.0],
isAStaticObject=True)
cube = Cube(rootNode,
uniformScale=20.0,
color=[1.0, 1.0, 0.0, 1.0],
totalMass=0.03,
volume=20,
inertiaMatrix=[1000.0, 0.0, 0.0, 0.0, 1000.0, 0.0, 0.0, 0.0, 1000.0],
translation=[0.0, -130.0, 10.0])
cube.addObject('UncoupledConstraintCorrection')
return rootNode
# -*- coding: utf-8 -*-
from stlib3.scene import MainHeader, ContactHeader
from stlib3.physics.rigid import Floor, Cube
from gripper import Gripper
def createScene(rootNode):
"""This is my first scene"""
MainHeader(rootNode, gravity=[0.0, -981.0, 0.0], plugins=["SoftRobots"])
ContactHeader(rootNode, alarmDistance=4, contactDistance=3, frictionCoef=0.08)
rootNode.VisualStyle.displayFlags = "showBehavior showCollisionModels"
Gripper(rootNode)
Floor(rootNode,
color=[1.0, 0.0, 0.0, 1.0],
translation=[0.0, -160.0, 0.0],
isAStaticObject=True)
cube = Cube(rootNode,
uniformScale=20.0,
color=[1.0, 1.0, 0.0, 1.0],
totalMass=0.03,
volume=20,
inertiaMatrix=[1000.0, 0.0, 0.0, 0.0, 1000.0, 0.0, 0.0, 0.0, 1000.0],
translation=[0.0, -130.0, 10.0])
cube.addObject('UncoupledConstraintCorrection')
return rootNode
笔记这样记太长了,剩下的内容放到另一篇里吧。