最近搞机械臂的末端夹具,本来想用吸盘的插件的,不知道为什么吸盘吸不起来可乐瓶,后面就换成夹爪了。
因为原厂的urdf文件中提供夹爪是用mimic标签控制剩下的5个joint关节的,网上参考的资料太少了,也是废了好多力
气,记一下这个希望帮到后面的人。
- 下载插件并编译生成.so文件
下载地址:https://github.com/roboticsgroup/roboticsgroup_gazebo_plugins
下载并catkin_make编译生成两个so文件
https://github.com/mintar/mimic_joint_gazebo_tutorial这个仓库告诉了我们怎么使用它,但是内容太少了好多东西没有说清楚
2. 插件注意事项
这里首先说一下使用事项:
-
切记从动装置不要写执行器
-
只用控制主的joint就行了
-
其次的话从动装置这里一定一定要写false,不然就出现下面的情况
- 插件使用
首先把插件引入的模型文件,cv就行辣
<xacro:macro name="mimic_joint_plugin_gazebo" params="name_prefix parent_joint mimic_joint has_pid:=false multiplier:=1.0 offset:=0 sensitiveness:=0.0 max_effort:=1.0 robot_namespace:=''"><gazebo><plugin name="${name_prefix}mimic_joint_plugin" filename="libroboticsgroup_gazebo_mimic_joint_plugin.so"><joint>${parent_joint}</joint><mimicJoint>${mimic_joint}</mimicJoint><xacro:if value="${has_pid}"> <!-- if set to true, PID parameters from "/gazebo_ros_control/pid_gains/${mimic_joint}" are loaded --><hasPID /></xacro:if><multiplier>${multiplier}</multiplier><offset>${offset}</offset><sensitiveness>${sensitiveness}</sensitiveness> <!-- if absolute difference between setpoint and process value is below this threshold, do nothing; 0.0 = disable [rad] --><maxEffort>${max_effort}</maxEffort> <!-- only taken into account if has_pid:=true [Nm] --><xacro:unless value="${robot_namespace == ''}"><robotNamespace>${robot_namespace}</robotNamespace></xacro:unless></plugin></gazebo>
</xacro:macro>
下面就照着葫芦画瓢就行了,只要按照强调的部分就问题不大
<jointname="C2_Join6"type="revolute"><originxyz="-0.0223 0.003 0.035591"rpy="0 0 0" /><parentlink="4C2_Link4" /><childlink="4C2_Link6" /><axisxyz="0 -1 0" /><limitlower="0"upper="0.82"effort="1"velocity="1" /><mimic joint="C2_Join1" multiplier="1.0" offset="0.0"/></joint><xacro:mimic_joint_plugin_gazebo name_prefix="C2_Join2"parent_joint="C2_Join1" mimic_joint="C2_Join2"has_pid="false" multiplier="1.0" max_effort="10.0" /> <xacro:mimic_joint_plugin_gazebo name_prefix="C2_Join3"parent_joint="C2_Join1" mimic_joint="C2_Join3"has_pid="false" multiplier="-1.0" max_effort="10.0" /> <xacro:mimic_joint_plugin_gazebo name_prefix="C2_Join4"parent_joint="C2_Join1" mimic_joint="C2_Join4"has_pid="false" multiplier="-1.0" max_effort="10.0" /> <xacro:mimic_joint_plugin_gazebo name_prefix="C2_Join5"parent_joint="C2_Join1" mimic_joint="C2_Join5"has_pid="false" multiplier="1.0" max_effort="10.0" /> <xacro:mimic_joint_plugin_gazebo name_prefix="C2_Join6"parent_joint="C2_Join1" mimic_joint="C2_Join6"has_pid="false" multiplier="1.0" max_effort="10.0" />
这里是加载成功的标志
如果按照说明的来就可以看到我们的末端夹具是OK的了