epson配置夹爪实现moveit仿真
1、epson机械臂配置
cd /home/hzx/robot_fd/epson_robot_with_slide_gripper_ws/src/epson3_description/urdf/xacro/
gedit epson3_with_slide_gripper.urdf.xacro
// 填入如下内容:
<?xml version="1.0"?>
<robot name="epson3" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:property name="M_PI" value="3.1415926536"/>
<xacro:include filename="$(find epson3_description)/urdf/xacro/materials.urdf.xacro" /> <!-- 没用到, -->
<xacro:include filename="$(find epson3_description)/urdf/xacro/slide_gripper.xacro" /> <!-- 1、夹爪相关:文件包含,将夹爪内容引入 -->
<link name="world" />
<joint name="world_joint" type="fixed">
<parent link="world" />
<child link = "base_footprint" />
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
</joint>
<link name="base_footprint"/>
<joint name="joint_0" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0" />
<parent link="base_footprint" />
<child link="base_link" />
</joint>
<link name="base_link">
<inertial>
<origin xyz="0.00018683 -0.033594 0.20677" rpy="0 0 0" />
<mass value="1.0752" />
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://epson3_description/meshes/base_link.STL" />
</geometry>
<material name="">
<color rgba="0.79216 0.81961 0.93333 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://epson3_description/meshes/base_link.STL" />
</geometry>
</collision>
</link>
<joint name="joint1" type="revolute">
<origin xyz="-0.00010776 -0.19479 0.026947" rpy="-0.0085874 -0.0015526 -0.17886" />
<parent link="base_link" />
<child link="link1" />
<axis xyz="0 0 1" />
<limit lower="-3.1416" upper="3.1416" effort="100" velocity="1" />
</joint>
<link name="link1">
<inertial>
<origin xyz="0.0014735 0.033853 0.082851" rpy="0 0 0" />
<mass value="0.96932" />
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://epson3_description/meshes/link1.STL" />
</geometry>
<material name="">
<color rgba="0.79216 0.81961 0.93333 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://epson3_description/meshes/link1.STL" />
</geometry>
</collision>
</link>
<joint name="joint2" type="revolute">
<origin xyz="0 0.088 0.14423" rpy="1.3175 -1.6502E-16 -8.3267E-16" />
<parent link="link1" />
<child link="link2" />
<axis xyz="1 0 0" />
<limit lower="-3.1416" upper="3.1416" effort="100" velocity="1" />
</joint>
<link name="link2">
<inertial>
<origin xyz="-0.00043816 -0.0041897 0.18164" rpy="0 0 0" />
<mass value="1.4945" />
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://epson3_description/meshes/link2.STL" />
</geometry>
<material name="">
<color rgba="0.79216 0.81961 0.93333 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://epson3_description/meshes/link2.STL" />
</geometry>
</collision>
</link>
<joint name="joint3" type="revolute">
<origin xyz="0 0 0.4" rpy="0.29389 8.3267E-17 6.9389E-17" />
<parent link="link2" />
<child link="link3" />
<axis xyz="1 0 0" />
<limit lower="-3.1416" upper="3.1416" effort="100" velocity="1" />
</joint>
<link name="link3">
<inertial>
<origin xyz="0.0066105 -0.0050668 0.021241" rpy="0 0 0" />
<mass value="0.63776" />
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://epson3_description/meshes/link3.STL" />
</geometry>
<material name="">
<color rgba="0.79216 0.81961 0.93333 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://epson3_description/meshes/link3.STL" />
</geometry>
</collision>
</link>
<joint name="joint4" type="revolute">
<origin xyz="0.00209 0.066487 0.04" rpy="3.1416 0.11662 3.1416" />
<parent link="link3" />
<child link="link4" />
<axis xyz="0 1 0" />
<limit lower="-3.1416" upper="3.1416" effort="100" velocity="1" />
</joint>
<link name="link4">
<inertial>
<origin xyz="-0.0005884 0.16402 0.0012711" rpy="0 0 0" />
<mass value="0.90708" />
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://epson3_description/meshes/link4.STL" />
</geometry>
<material name="">
<color rgba="0.79216 0.81961 0.93333 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://epson3_description/meshes/link4.STL" />
</geometry>
</collision>
</link>
<joint name="joint5" type="revolute">
<origin xyz="0 0.33751 0" rpy="1.0901 -3.5527E-15 -3.034E-15" />
<parent link="link4" />
<child link="link5" />
<axis xyz="-1 0 0" />
<limit lower="-3.1416" upper="3.1416" effort="100" velocity="1" />
</joint>
<link name="link5">
<inertial>
<origin xyz="0.00031266 0.018226 0.00022481" rpy="0 0 0" />
<mass value="0.15732" />
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://epson3_description/meshes/link5.STL" />
</geometry>
<material name="">
<color rgba="0.79216 0.81961 0.93333 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://epson3_description/meshes/link5.STL" />
</geometry>
</collision>
</link>
<joint name="joint6" type="revolute">
<origin xyz="0 0.061439 0" rpy="-3.1416 0.030603 3.1416" />
<parent link="link5" />
<child link="link6" />
<axis xyz="0 -1 0" />
<limit lower="-3.1416" upper="3.1416" effort="100" velocity="1" />
</joint>
<link name="link6">
<inertial>
<origin xyz="-5.5511E-17 0.0069965 7.9575E-05" rpy="0 0 0" />
<mass value="0.027204" />
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://epson3_description/meshes/link6.STL" />
</geometry>
<material name="">
<color rgba="0.74902 0.74902 0.74902 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://epson3_description/meshes/link6.STL" />
</geometry>
</collision>
</link>
<link name="tool0"/>
<joint name="joint_tool0" type="fixed">
<origin xyz="0 -0.013 0" rpy="0 0 0" />
<parent link="link6" />
<child link="tool0" />
</joint>
<!-- Transmissions for ROS Control -->
<xacro:macro name="transmission_block" params="joint_name">
<transmission name="tran1">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${joint_name}">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="motor1">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</xacro:macro>
<xacro:transmission_block joint_name="joint1"/>
<xacro:transmission_block joint_name="joint2"/>
<xacro:transmission_block joint_name="joint3"/>
<xacro:transmission_block joint_name="joint4"/>
<xacro:transmission_block joint_name="joint5"/>
<xacro:transmission_block joint_name="joint6"/>
<xacro:transmission_block joint_name="strack_base_joint1"/> <!-- 2、夹爪相关:为两个可动关节添加传动 -->
<xacro:transmission_block joint_name="strack_base_joint2"/> <!-- 3、夹爪相关:不可动关节【fixed】不必添加传动 -->
<!-- ros_control plugin -->
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/epson3</robotNamespace>
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
<legacyModeNS>true</legacyModeNS>
</plugin>
</gazebo>
<!--
<gazebo>
<plugin name="gazebo_grasp_fix" filename="libgazebo_grasp_fix.so">
<arm>
<arm_name>epson3_slide_gripper</arm_name>
<palm_link> gripper_base_link_joint </palm_link>
<gripper_link>gripper_base_link</gripper_link>
<gripper_link> strack_link1 </gripper_link>
<gripper_link> strack_link2 </gripper_link>
</arm>
<forces_angle_tolerance>100</forces_angle_tolerance>
<update_rate>4</update_rate>
<grip_count_threshold>4</grip_count_threshold>
<max_grip_count>8</max_grip_count>
<release_tolerance>0.005</release_tolerance>
<disable_collisions_on_attach>true</disable_collisions_on_attach>
<contact_topic>__default_topic__</contact_topic>
</plugin>
</gazebo>
-->
</robot>
2、自定义夹爪
// 编写夹爪
cd /home/hzx/robot_fd/epson_robot_with_slide_gripper_ws/src/epson3_description/urdf/xacro/
gedit slide_gripper.xacro // 滑动方式的夹爪【slide v 滑动】
// 填入如下内容
<!--
一点经验:
当编写 link1——joint——link2 结构的结构时,需要注意:
编写好link1后,先配置 joint 相对于 link1 的位姿【需考虑 link1 的几何尺寸】,再配置 link2 相对于 joint 的位姿【需考虑 link2 的尺寸】
具体可见夹爪相关link 与 joint 的编写方式。
-->
<?xml version="1.0" encoding="utf-8"?>
<robot name="slide_gripper" xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:property name="base_link_length" value="0.3" />
<xacro:property name="base_link_width" value="0.05" />
<xacro:property name="base_link_height" value="0.02" />
<!--该关节用来连接机械臂末端与夹爪基座 -->
<joint name="gripper_base_link_joint" type="fixed">
<parent link="tool0"/>
<child link="gripper_base_link"/>
<origin xyz="0 0.045 0" rpy="1.57 0 0"/> <!-- 0.04就已经很好贴合了 -->
<axis xyz="1 0 0"/>
<limit lower="-0.145" upper="0" effort="100" velocity="3" />
</joint>
<!-- 夹爪基座 要设置相应的 visual interial 与 collision,不然配置moveit时夹爪会出问题 -->
<link name="gripper_base_link">
<inertial> <!-- 惯性矩阵可以设置为10 质量可以设置为 0.01 -->
<mass value="0.01"/>
<origin xyz="0 0 0"/>
<inertia ixx="1.0" ixy="1.0" ixz="1.0" iyy="1.0" iyz="1.0" izz="1.0"/>
</inertial>
<collision> <!-- 碰撞几何一般就是外观几何 -->
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="${base_link_length} ${base_link_width} ${base_link_height}" />
</geometry>
</collision>
<visual>
<geometry>
<box size="${base_link_length} ${base_link_width} ${base_link_height}" />
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
<material name="Blue">
<color rgba="1 0 0 1"/>
</material>
</visual>
</link>
<!-- 夹爪1 -->
<link name="strack_link1">
<inertial>
<mass value="0.01"/>
<origin xyz="0 0 0"/>
<inertia ixx="1.0" ixy="1.0" ixz="1.0" iyy="1.0" iyz="1.0" izz="1.0"/>
</inertial>
<collision>
<origin xyz="0.01 0 -0.1" rpy="0 0 0"/>
<geometry>
<box size="0.02 0.05 0.2" />
</geometry>
</collision>
<visual>
<geometry>
<box size="0.02 0.05 0.2" />
</geometry>
<origin xyz="0.01 0 -0.1" rpy="0 0 0"/>
<material name="Blue2">
<color rgba="0 0.3 0.4 1"/>
</material>
</visual>
</link>
<!-- 夹爪1与夹爪基座的相连关节,此处关节type为 滑动 -->
<joint name="strack_base_joint1" type="prismatic">
<parent link="gripper_base_link"/>
<child link="strack_link1"/>
<origin xyz="0.15 0 -0.01" rpy="0 0 0"/> <!-- 关节安装在父级连杆的相对位置,然后调整连杆偏移角度【相对于父级连杆的长宽高的一半】 -->
<axis xyz="1 0 0"/>
<limit lower="-0.145" upper="0" effort="100" velocity="3" />
</joint>
<!-- 夹爪2 -->
<link name="strack_link2">
<inertial>
<mass value="0.01"/>
<origin xyz="0 0 0"/>
<inertia ixx="1.0" ixy="1.0" ixz="1.0" iyy="1.0" iyz="1.0" izz="1.0"/>
</inertial>
<collision>
<origin xyz="0.01 0 -0.1" rpy="0 0 0"/>
<geometry>
<box size="0.02 0.05 0.2" />
</geometry>
</collision>
<visual>
<geometry>
<box size="0.02 0.05 0.2" />
</geometry>
<origin xyz="0.01 0 -0.1" rpy="0 0 0"/>
<material name="Blue2">
<color rgba="0 0.3 0.4 1"/>
</material>
</visual>
</link>
<!-- 夹爪2与夹爪基座的相连关节,此处关节type为 滑动 -->
<joint name="strack_base_joint2" type="prismatic">
<parent link="gripper_base_link"/>
<child link="strack_link2"/>
<origin xyz="-0.15 0 -0.01" rpy="0 0 3.14"/>
<axis xyz="1 0 0"/>
<limit lower="-0.145" upper="0" effort="100" velocity="3" />
</joint>
</robot>
3、配置moveit
0、 启动moveit助手
cd /robot_fd/epson_robot_with_slide_gripper_ws$
hzx@vm:~/robot_fd/epson_robot_with_slide_gripper_ws$ source devel/setup.bash
hzx@vm:~/robot_fd/epson_robot_with_slide_gripper_ws$ roslaunch moveit_setup_assistant setup_assistant.launch
1、导入机械臂+夹爪的 xacro文件 /home/hzx/robot_fd/epson_robot_with_slide_gripper_ws/src/epson3_description/urdf/xacro/epson3_with_slide_gripper.urdf.xacro ,加载成功过后,右边会出现一个机械臂模型。
2 、自动生成碰撞检测
默认的碰撞免检矩阵生成器搜索机器人所有关节,碰撞检测是检测两个连杆是否有接触,这个碰撞免检矩阵是可以安全地关闭检查,从而减少行动规划的处理时间。比如相邻的两个连杆因为是通过关节连接起来的,但实际上这不是碰撞。所以可以不用去费时间检查。
3、创建虚拟关节,用于连接机械臂与世界
添加虚拟关节主要是把机械臂关联到world。这里我们只需要定义一个虚拟关节把base_link关联到world,从而定义机械臂基座和world的坐标系关系。
4、创建两个分组,一个是机械臂的全部关节【ur5_arm】,一个是夹爪的全部关节【gripper】
oveIt 通过定义规划组(planning group)来语义上定义机机械臂的各个部分(如手臂,末端执行器等)。这是MoveIt中一个很重要的概念。简单来说就是定义某些关节为一个组合并起一个名字。这里我添加了两个规划组,一个是arm,一个是gripper,后面使用moveit提供的python接口会用到,arm控制机械臂运动,gripper控制夹爪运动。
————————————————
原文链接:https://blog.csdn.net/leng_peach/article/details/131931554
5、配置机械臂与夹爪的初始位姿
6、配置末端执行器 ,这里我用的是gripper组连接到机械臂末端上
7、配置被动 第七步:被动关节设置,因为机械臂没有被动关节,所以可以跳过
8 、配置控制器 自动生成arm和gripper的控制器
9、人员信息
10 、生成配置文件