Gazebo插件Grasp_fix介绍与踩坑(识别不到物体,抓取时掉落)
Gazebo插件Grasp_fix介绍0.踩的坑1.Grasp_fix插件下载2.插件介绍一、如何使用二、各参数含义0.踩的坑在抓物体时,可能物体很小,只能用夹爪的前端的尖尖去抓,这样这个插件是很难检测到的,比如我一开始的这个物体就太薄了,不管怎么样设置插件的参数都抓不起来直到后来我换成了圆柱,突然发现能识别到物体了,才意识到物体的厚度问题,后来把这个长方体厚度加大,成功抓起来了可以考虑适当增加物
Gazebo插件Grasp_fix介绍
0.踩的坑
在抓物体时,可能物体很小,只能用夹爪的前端的尖尖去抓,这样这个插件是很难检测到的,比如我一开始的这个物体就太薄了,不管怎么样设置插件的参数都抓不起来
直到后来我换成了圆柱,突然发现能识别到物体了,才意识到物体的厚度问题,后来把这个长方体厚度加大,成功抓起来了
可以考虑适当增加物体的厚度,也就是让物体的更多部分和夹爪发生接触,这样能够更容易检测到物体,才能抓起来。
1.Grasp_fix插件下载
这个插件来自JenniferBuehler大佬,主要解决了在Gazebo中机械夹爪在抓取物体时出现的掉落和抖动等问题,在检测到机械爪与物体发生接触或碰撞时,就会把夹爪和物体合成一个整体,这样就能够防止物体抓不起来的情况。
下载地址:https://github.com/JenniferBuehler/gazebo-pkgs/tree/master/gazebo_grasp_plugin
这个插件的官方介绍在wiki上有:https://github.com/JenniferBuehler/gazebo-pkgs/wiki/The-Gazebo-grasp-fix-plugin
2.插件介绍
一、如何使用
在urdf文件中加上以下代码,可以是机械臂的urdf,也可以是夹爪的
<gazebo>
<plugin name="gazebo_grasp_fix" filename="libgazebo_grasp_fix.so">
<arm>
<arm_name>ur5_gripper</arm_name>
<palm_link>wrist_3_link</palm_link>
<gripper_link>gripper_finger1_finger_tip_link</gripper_link>
<gripper_link>gripper_finger2_finger_tip_link</gripper_link>
<gripper_link>gripper_finger2_knuckle_link</gripper_link>
<gripper_link>gripper_finger1_knuckle_link</gripper_link>
<gripper_link>gripper_finger1_inner_knuckle_link</gripper_link>
<gripper_link>gripper_finger2_inner_knuckle_link</gripper_link>
</arm>
<forces_angle_tolerance>150</forces_angle_tolerance>
<update_rate>130</update_rate>
<grip_count_threshold>2</grip_count_threshold>
<max_grip_count>8</max_grip_count>
<release_tolerance>0.01</release_tolerance>
<disable_collisions_on_attach>true</disable_collisions_on_attach>
<contact_topic>__default_topic__</contact_topic>
</plugin>
</gazebo>
二、各参数含义
<arm_name>
应该是一个单独的名字,不能和别的任何关节同名<palm_link>
是和手指相连的关节,这里我直接用了机械臂末端关节,也没遇到啥问题<gripper_link>
是会检测碰撞的关节,建议把所有的机械爪关节都写上<forces_angle_tolerance>
这个检测相互作用力,当两个力的夹角大于这个阈值时,才会被认为是相互作用力。插件的源程序中默认角度要大于90度,这里很好理解,两个力要朝相反的方向才符合相互作用力的条件,这里其实是检测夹爪和物体之间的相互作用力,夹爪和物体发生了接触,才会发生作用力,且如果夹爪和物体是平行的,力夹角应该是180度,这里其实设置阈值为90度或者120度就可以了。<update_rate>
是检测频率,建议稍微调高一点<grip_count_threshold>
是检测为抓取状态的接触次数阈值?就是在夹爪和物体之间会有接触,超过多少次之后会被抓起来,可能我理解的不正确,但是我觉得这个值太大了就会使物体被抓起来不是很容易<max_grip_count>
这个最好比上边的阈值大2倍,具体原因也不是很明白<release_tolerance>
这个很重要!!!不要设置太大,否则夹爪张开也不会把物体放下,会粘在夹爪上,这个就是释放时的容忍度,超过这个就会把物体放下。具体的可以在实验中慢慢试。<disable_collisions_on_attach>
这个也没理解啥意思,好像true
和false
都没影响,可能我没遇到复杂的情况。
总结一下,就是<release_tolerance>
很重要,会影响能不能放下物体,还有记得把物体厚度大一些,否则很难检测到物体。
最后附上成功的视频:(项目参考https://github.com/lihuang3/ur5_ROS-Gazebo)
UR5+Robotiq85抓取动态物体
更多推荐
所有评论(0)