Yahboom公司机械臂Dofbot从零部署笔记,看这篇的同学首先需要购买他们公司的Dofbot机械臂 + 树莓派组合,出厂已经配置好部署完毕的镜像。
需要适当的前置知识:什么是URDF模型、什么是moveit和轨迹规划。
一、创建URDF模型
1、创造新的工作空间
在根目录下创建工作空间
mkdir -p catkin_ws/src
cd catkin_ws/
catkin_make
进入src目录:
catkin_create_pkg dofbot_description urdf xacro
2、文件配置
进入dofbot_description目录,建立四个文件夹:
- urdf:存放机器人模型的URDF或xacro文件
- meshes:存放URDF中引用的模型渲染文件
- launch:保存相关启动文件
- config:保存rviz的配置文件
2.1 urdf文件
进入urdf目录,创建模型文件:
touch dofbot.urdf
dofbot机械臂的urdf模型
<?xml version="1.0" encoding="utf-8" ?>
<robot name="yahboom_dofbot">
<link name="base_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://dofbot_description/meshes/base_link.STL" />
</geometry>
<material name="">
<color rgba="0.2 0.2 0.2 1" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://dofbot_description/meshes/base_link.STL" />
</geometry>
</collision>
</link>
<link name="arm_link1">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://dofbot_description/meshes/visual/arm_link1.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://dofbot_description/meshes/collision/arm_link1.STL" />
</geometry>
</collision>
</link>
<joint name="arm_joint1" type="revolute">
<origin xyz="0 0 0.06605" rpy="-0.010805 0 1.5" />
<parent link="base_link" />
<child link="arm_link1" />
<axis xyz="0 0 1" />
<limit effort="30" velocity="10.0" lower="-1.5708" upper="1.5708" />
</joint>
<link name="arm_link2">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://dofbot_description/meshes/visual/arm_link2.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://dofbot_description/meshes/collision/arm_link2.STL" />
</geometry>
</collision>
</link>
<joint name="arm_joint2" type="revolute">
<origin xyz="0 0 0.0405" rpy="-1.5708 0 0" />
<parent link="arm_link1" />
<child link="arm_link2" />
<axis xyz="0 0 -1" />
<limit lower="-1.5708" upper="1.5708" effort="100" velocity="10" />
</joint>
<link name="arm_link3">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://dofbot_description/meshes/visual/arm_link3.STL" />
</geometry>