准备:

  1. solidworks2022
  2. sw2urdf插件 github地址
  3. 一个被简化的模型
  • 介绍:
  • sw2urdf插件是一个ros社区开源的插件,支持将solidworks中的模型(只要是sw能打的开的模型文件)转为urdf描述的文件以及功能包。
  • 我们的机器人模型经过插件导出后生成的STL文件往往会有上百万的面,我们机器人端的设备性能不高,在使用moveit时往往需要花三分钟才能加载出来模型。使用简化的模型可以让moveit在几秒钟内完成加载。
  • 一般link是机器人的实体,joint是一个轴/轨(连接两个link的约束)。比如车身和轮子,车身为link0,轮子为link1,而轮子的轴线为joint。
  • joint通常使用的类型有revolute(有限旋转)、continuous(无限旋转)、fixed(固定)、floating(浮动)、planar(平面)、prismatic(平移)。机械臂上的摄像头与末端的固定连接为fixed,底盘与轮子的连接为continuous,机械臂的关节为revolute,直线导轨滑块的关节为prismatic。

演示:

  • 这是一个很简单的装配体,由两个零件组成。黄色零件为轮子,红色零件为车体。从前面的介绍不难知道,我们可以将这两个零件分别命名为base_link,link_wheel。

  • 轮子相对于车体的运动为连续旋转,那么根据前面的介绍,轮子与车体的关节类型为continuous。
  • 在开始导出为urdf前,需要增加一些参考坐标轴、线和点。

  • 参考点的选择决定坐标系的位置。以黄色零件轮子为例,需要保证的是轮子的坐标系理应有某一轴和轮子轴线重合,至于说坐标系的原点是在左圆面上还是右圆面上,或是几何中心,都可以。这里我选择坐标系原点在左端面上。具体,首先选择增加参考线,这个线的参考对象为圆柱面。随后选择增加参考点,这个点的参考对象为前面的参考线与左端面。最后选择增加参考坐标系,这个坐标系的参考对象为前面的参考点。

  • 红色零件的参考坐标系和前面同样设置。
  • 在solidworks上方,点工具,然后在下拉菜单里下翻找到Tools,选择Export as URDF

  • 随后出现这个界面

  • 选择base_link的参考坐标系,并选择base_link的实体,选择实体点击对应的模型即可

  • 点击增加一个子link

  • 最后这样配置,点击Preview and Export 即可

接下来我展示一下我们的机器人的最终设计模型以及简化模型:

简化后的模型文件大小连1mb都没有,配合moveit!打开rviz时仅仅只要四秒的时间,如果是原本的模型将会需要三分钟。

这里我展示一下简化模型上标设的参考坐标系以及生成的功能包下的urdf文件部分参数。

<joint name="slide_link_joint" type="prismatic">
    <origin xyz="0 -0.22 0.33" rpy="0 0 -1.5708" />
    <parent link="base_link" />
    <child link="slide_link" />
    <axis xyz="0 0 1" />
    <limit lower="-0.2" upper="0.2" effort="0" velocity="0" />
</joint>

joint里面的参数 axis代表着child link沿着parent link的z方向转动/移动。在prismatic关节类型里,意味着沿着z方向移动。这里所谓的z方向是我们在solidworks中添加的link的参考坐标系的z方向。

参数limit 里面的lower和upper往往意味着这个关节的运动限幅。对于continuous关节类型,limit下应该是没有这两个参数,而对于revolute来说意味着旋转关节的角度限幅,对于prismatic来说意味着直线移动的距离限幅。

参数limit下的参数往往影响着机器人关节的控制。对于位置控制,lower和upper限制了关节的运动范围,而对于力矩控制,effort代表着关节的最大输出扭矩,对于速度控制,velocity代表着关节的最大转动/移动速度。

<link name="slide_link">
  <inertial>
    <origin xyz="-2.7756E-17 -6.3759E-17 0.0075" rpy="0 0 0" />
    <mass value="0.231" />
    <inertia ixx="0.00019683" ixy="-2.1029E-20" ixz="-3.641E-20" iyy="0.00046086" iyz="1.7113E-20" izz="0.00064903" />
  </inertial>
  <visual>
    <origin xyz="0 0 0" rpy="0 0 0" />
    <geometry>
      <mesh filename="package://simple_only_arm/meshes/slide_link.STL" />
    </geometry>
    <material name="">
      <color rgba="1 1 1 1" />
    </material>
  </visual>
  <collision>
    <origin xyz="0 0 0" rpy="0 0 0" />
    <geometry>
      <mesh filename="package://simple_only_arm/meshes/slide_link.STL" />
    </geometry>
  </collision>
</link>

link里面的参数分为三个部分,inertial(惯性的)、visual(可视化的)、collision(碰撞)。对于我们要在moveit!中控制机械臂,首要需要的是collision。ompl这个开源运动规划库中,每一次做规划不仅仅是对机械臂做逆解,更需要计算每个link之间的碰撞关系。如果我们需要对机械臂做力矩控制或力位混合控制就需要用到inertial参数了,这里面mass是质量,inertia是惯性矩,特别注意的是这里的origin与其他参数里的origin不一样,这里的指的是重心,而不是参考坐标原点。

下篇博客预备:

  • 在旭日X3派安装原生ROS1:

          使用鱼香ROS的一键安装命令:

wget http://fishros.com/install -O fishros && . fishros

地平线是有提供基于ros2 foxy二次开发的tros,我没有时间去移植我的代码所以还是沿用ros1.

  • 在安装成功后,发现打开rviz有问题,是一些关于opengl库的报错
libEGL warning: DRI2 :failed to authenticate

以及其他的,这里就不多放了,解决方法很简单

sudo apt-get install libgl1*

然后reboot就行了