怎么说呢!URDF 文件确实是一种非常重要的机械臂关节描述文件,但是还不够灵活,我们可以将它升级成XACRO文件(实际上,确实需要修改成这个类型的文件),在原来的基础上添加了一些代码!
在修改过程中,我会指出其中的一些需要注意的点,以及其中造成机械臂瘫倒,以及颤抖的原因!
我们在src文件夹中打开urdf文件,如下:
我们复制一份,并且可以直接修改后缀,修改成了robot2600_20_simulation.xacro,如下图:
首先,我们双击点开robot2600_20_simulation.xacro,将开头修改一下。
修改前:
<robot
name="robot2600_20">
修改后:
<robot name="robot2600_20" xmlns:xacro="http://ros.org/wiki/xacro">
其次,添加一个虚拟的世界坐标,如下图,让它和base_link固定在一起,大家一定要添加这个虚拟的固定坐标,因为要防止自己的机械臂在天上飞,或者整体倒下。当然,你添加了之后,base_link不会倒下,但是机械臂还暂时抬不起来!别急且看后续!
<link name="world"/>
<joint name="fixed_base_joint" type="fixed">
<parent link="world"/>
<child link="base_link"/>
</joint>
然后,为每一个joint添加gazebo使用的transmission标签,(这一段代码非常长,但是应该非常好理解)大家可以理解为给每一个关节仿真添加了驱动设备,必须有执行器,后面才可以进行驱动。
<xacro:macro name="transmission_block" params="tran_name joint_name motor_name">
<transmission name="${tran_name}">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${joint_name}">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="$motor_name">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</xacro:macro>
<xacro:transmission_block tran_name="tran1" joint_name="joint1" motor_name="motor1"/>
<xacro:transmission_block tran_name="tran2" joint_name="joint2" motor_name="motor2"/>
<xacro:transmission_block tran_name="tran3" joint_name="joint3" motor_name="motor3"/>
<xacro:transmission_block tran_name="tran4" joint_name="joint4" motor_name="motor4"/>
<xacro:transmission_block tran_name="tran5" joint_name="joint5" motor_name="motor5"/>
<xacro:transmission_block tran_name="tran6" joint_name="joint8_left" motor_name="motor6"/>
<xacro:transmission_block tran_name="tran7" joint_name="joint8_right" motor_name="motor7"/>
一定要注意这里:
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
有的朋友写的是这个:
<hardwareInterface>hardwareInterface/EffortJointInterface</hardwareInterface>
这两种有什么区别呢?第一种是关节的位置控制,第二种是关节的力矩控制。如果选择第一种,那我们关心的更多是机械臂关节运动的位置,更多忽略每一个关节驱动的力矩。事实上,我们确实更想关心位置既轨迹,这足够了!
如果选择第一种,那么恭喜你,你的机械臂后面运行起来基本不会抬不起来,嘿嘿!
如果选择第二种,那你需要关心inertial里面的参数是否正确,大家可能会问,inertial在哪里?
<inertial>
<origin
xyz="-0.08155265 0.00029774 0.09394993"
rpy="0 0 0" />
<mass
value="0.00001" />
<inertia
ixx="0.47864391"
ixy="0.00366749"
ixz="0.02583563"
iyy="0.93676866"
iyz="0.00048946"
izz="1.20994094" />
</inertial>
如下两个参数需要关心:
第一:mass参数,这个是在Solidworks中导出URD文件的时候,自动给每一个link评估的质量,大家点击太快,可能忘记了这个,单位是Kg。如果这个的数值很大,比如说33.656Kg,那么这个关节会非常重,你的关节力矩无法将这个关节驱动起来,那么就算你添加了transmission,并且添加了控制部分,机械臂也会呈现一种半萎靡状态。这是一种机械臂抬不起来的因素。
怎么办呢?好办,像我一样,如果要求不是很大,直接改成0.00001就行了!
第二:inertia参数,这又是什么东西呢?这个就是惯性矩阵,这个的参数不准确是导致机械臂抖动的重要因素。这玩意怎么修改呢?这里展不开,要使用Solidworks中的质量评估这个功能。
注意:如果是我们在官网下载的这种机械臂,每一个关节分好了,评估的还是比较准确的,如果是我们自己画的非标机构添加进去了,比如我这里加了一个自己画的机械夹爪,自动评估的就不是很准确了,需要我们自己去评估修改一下,起到优化的作用。这可以减小抖动。
再次,添加gazebo_ros_control插件,将ros和gazebo连接起来,代码如下:
我给每一个Link都添加了一个颜色,哈哈!可能看起来更好看一点吧!强迫症啊!
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/robot2600_20</robotNamespace>
<legacyModeNS>true</legacyModeNS>
</plugin>
</gazebo>
<gazebo reference="base_link">
<material>Gazebo/White</material>
</gazebo>
<gazebo reference="link1">
<material>Gazebo/Orange</material>
</gazebo>
<gazebo reference="link2">
<material>Gazebo/White</material>
</gazebo>
<gazebo reference="link3">
<material>Gazebo/Orange</material>
</gazebo>
<gazebo reference="link4">
<material>Gazebo/White</material>
</gazebo>
<gazebo reference="link5">
<material>Gazebo/Orange</material>
</gazebo>
<gazebo reference="link6">
<material>Gazebo/White</material>
</gazebo>
<gazebo reference="link7">
<material>Gazebo/White</material>
</gazebo>
<gazebo reference="link8_left">
<material>Gazebo/Orange</material>
</gazebo>
<gazebo reference="link8_right">
<material>Gazebo/Orange</material>
</gazebo>
再再次:修改display.launch文件,这样可以在Rviz中展示
<param name="robot_description"
command="$(find xacro)/xacro --inorder '$(find robot2600_20)/urdf/robot2600_20_simulation.xacro'" />
再再再次:修改gazebo.launch文件
在头部添加如下代码:
<param name="robot_description"
command="$(find xacro)/xacro --inorder '$(find robot2600_20)/urdf/robot2600_20_simulation.xacro'" />
然后对"spawn_model"结点中的args进行修改,
修改前:
<node
name="spawn_model"
pkg="gazebo_ros"
type="spawn_model"
args="-file $(find robot2600_20)/urdf/robot2600_20.urdf -urdf -model robot2600_20"
output="screen" />
修改后:
<node
name="spawn_model"
pkg="gazebo_ros"
type="spawn_model"
args="-urdf -model robot2600_20 -param robot_description"
output="screen" />
再再再再次:我们分别运行一下display.launch文件和gazebo.launch文件看看,能不能正常显示出来。
display.launch文件当然能够运行啦!肯定不用说,但是上图是运行gazebo.launch文件之后的效果,而且是选择hardware_interface/PositionJointInterface运行之后的效果。如果你选择第二种,并且相应的参数都调整了,那么一打开后的现象是:机械臂竟然抬起来了,但是逐渐萎靡,越来越萎靡,最后倒下!当然我没有暗指什么,嘿嘿!
解决逐渐倒下的方法是什么呢?也不是说方法吧!不管你选择位置控制还是力矩控制,都必须添加如下控制部分的内容,只是说添加了之后,对于第一种选择位置控制的朋友,没有什么现象可见,但是对于选择第二种力矩控制的朋友,会发现机械臂不会逐渐倒下,会保持住抬起的状态。
创建控制功能包
我们在src文件夹下创建一个功能包,这一步大家应该会,如下:
cd ~/catkin_ws/src
catkin_create_pkg robot2600_20_control controller_manager joint_state_controller robot_state_publisher
cd robot2600_20_control
mkdir config
mkdir launch
再再再再再次:我们在robot2600_20_control的config文件夹下创建robot2600_20_control.yaml文件,这个后缀的文件是参数文件。打开该文件后写入:
robot2600_20:
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 50
joint1_position_controller:
type: position_controllers/JointPositionController
joint: joint1
pid: {p: 100.0, i: 0.01, d: 10.0}
joint2_position_controller:
type: position_controllers/JointPositionController
joint: joint2
pid: {p: 100.0, i: 0.01, d: 10.0}
joint3_position_controller:
type: position_controllers/JointPositionController
joint: joint3
pid: {p: 100.0, i: 0.01, d: 10.0}
joint4_position_controller:
type: position_controllers/JointPositionController
joint: joint4
pid: {p: 100.0, i: 0.01, d: 10.0}
joint5_position_controller:
type: position_controllers/JointPositionController
joint: joint5
pid: {p: 100.0, i: 0.01, d: 10.0}
joint8left_position_controller:
type: position_controllers/JointPositionController
joint: joint8_left
pid: {p: 1, i: 0.001, d: 0.002}
joint8right_position_controller:
type: position_controllers/JointPositionController
joint: joint8_right
pid: {p: 1, i: 0.001, d: 0.002}
这里的关节不要写错了,尤其是Type如果是像我这样选择第一种一定要对应写position_controllers/JointPositionController,因为这里和xacro文件中的transmission是对应的。
选择第二种就写effort_controllers/JointPositionController
再再再再再次:在robot2600_20_control的launch文件夹下创建robot2600_20_control.launch文件,注意后缀是launch文件。打开后写入:
<launch>
<rosparam file="$(find robot2600_20_control)/config/robot2600_20_control.yaml" command="load"/>
<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
output="screen" ns="/robot2600_20" args="joint1_position_controller joint2_position_controller joint3_position_controller joint4_position_controller joint5_position_controller joint8left_position_controller joint8right_position_controller joint_state_controller"/>
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"
respawn="false" output="screen">
<remap from="/joint_states" to="/robot2600_20/joint_states" />
</node>
</launch>
再再再再再再次:在robot2600_20的launch文件夹中的gazebo.launch文件中添加如下代码:
<include file="$(find robot2600_20_control)/launch/robot2600_20_control.launch" />
意思就是,在运行gazebo.launch仿真文件的同时,运行控制文件。
最后再catkin_ws根目录下编译一下就行了,目前为止,大功告成!
测试的时候直接运行roslaunch robot2600_20 gazebo.launch就行了
再说一点,对于选择第一种位置控制方式的朋友,发现加了控制文件之后,没什么现象,但是对于选择第二种力矩控制的朋友,会发现你的机械臂不会再逐渐萎靡下去了。比方说,你可以让你的机械臂先萎靡一半然后再单独运行控制文件,会发现你的机械臂保持在萎靡一半的位置,这应该就是PID控制的效果了。
好了,说完了,拜拜!