大家如果阅读过或者尝试写过urdf文件就会发现. 这玩意儿真是又臭又长, 反正我不是很愿意自己去写, 而且一整还总写错. ROS官方提供了一个基于Solidworks的插件, 可以让我们比较方便地生成一个ROS的机器人description功能包, 其中包含了display和gazebo两个demo性质的.launch文件, 可以粗粗看一下自己生成的模型是否正确.
本文并不主要聚焦于Solidworks导出ROS功能包的具体操作. 大家可以去网上搜索一些其他的教程.
下面我将会基于这个从solidworks中导出的功能包, 对之进行修改, 然后实现在Gazebo中实现初步的仿真和修改.
本文的介绍并不全面, 而更像是一个感性的体验性质的过程, 如果想要了解更多, 还是建议去官网看wiki
首先我们创建一个新的工作空间:
mkdir -p ~/new_ws/src
cd ~/new_ws/src
catkin_init_workspace
cd ..
catkin_make
这些命令执行完之后, 执行sudo nano ~/.bashrc在文件的最后加上source /home/XXXX/new_ws/devel/setup.bash其中XXXX按照实际状况填入.
在这之后, 把当前的终端关闭. 然后在new_ws下的src中粘贴提供的sixaxis_description.
打开一个新的终端.
cd new_ws
catkin_make
记得修改~/.bashrc中的内容, 把新的工作空间添加到环境变量当中.
功能包导出完成, 我们打开功能包中launch文件夹下的display.launch文件, 把第6行中gui的选项改为true. 保存关闭. 然后在终端中输入:
roslaunch sixaxis_description display.launch
在rviz中把Global Options下的Fixed Frame改为base_link. 点击左下角的add, 选择其中的RobotModel. 然后就可以看到机械臂模型啦!
我们主要需要向urdf文件中加入transmission元素和添加gazebo_ros_control插件. 为了加入transmission元素时的方便, 我们可以考虑将利用xacro来修改urdf.
首先把原来的文件名从sixaxis_description.urdf改为sixaxis.xacro
我们首先修改一下文件一开始的robot标签, 把本来的:
<robot
name="sixaxis_description">
改为
<robot name="sixaxis" xmlns:xacro="http://ros.org/wiki/xacro">
找一个合适的文本编辑器, 选择替换, 把所有的continuous替换为revolute
然后把每一个joint修改成形如下面的样子:
<joint
name="joint1"
type="revolute">
<origin
xyz="0 0 0.04"
rpy="0 0 -1.5708" />
<parent
link="base_link" />
<child
link="link1" />
<axis
xyz="0 0 1" />
<dynamics damping="0.7"/>
<limit effort="300" velocity="1" lower="-2.96" upper="2.96"/>
joint>
在文件的最后加入:
joint>
<xacro:macro name="transmission_block" params="tran_name joint_name motor_name">
<transmission name="${tran_name}">
<type>transmission_interface/SimpleTransmissiontype>
<joint name="${joint_name}">
<hardwareInterface>hardware_interface/EffortJointInterfacehardwareInterface>
joint>
<actuator name="$motor_name">
<hardwareInterface>hardware_interface/EffortJointInterfacehardwareInterface>
<mechanicalReduction>1mechanicalReduction>
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="joint6" motor_name="motor6"/>
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/sixaxisrobotNamespace>
plugin>
gazebo>
robot>
这样一来, xacro文件就已经建立好了.(注意, 这边的transmission标签当中的hardware_interface可以如我所写的选择EffortJointInterface, 同样也可以选择PositionJointInterface, 但是需要在后续建立的yaml文件中也进行相应的修改.)
我们修改一下launch文件夹下的display.launch文件:
把其中的一个param "robot_discription"的一整个标签修改为如下的形式:
<param name="robot_description"
command="$(find xacro)/xacro --inorder '$(find sixaxis_description)/urdf/sixaxis.xacro'" />
我们也修改一下gazebo.launch文件, 在其中先加入之前经过修改后的变量:
<param name="robot_description"
command="$(find xacro)/xacro --inorder '$(find sixaxis_description)/urdf/sixaxis.xacro'" />
然后对需要启动的"spawn_model"结点中的args进行修改, 改为:
args="-urdf -model newaxis -param robot_description"
这个时候我们可以测试一下roslaunch sixaxis_descritpion display.launch以及roslaunch sixaxis_descritpion gazebo.launch还能否正确显示, 要是可以的话, 我们就可以进入下一步了.
我们先生成一个新的工作包用来存储控制部分的内容:
cd ~/new_ws/src
catkin_create_pkg sixaxis_control controller_manager joint_state_controller robot_state_publisher
cd sixaxis_control
mkdir config
mkdir launch
我们首先在config当中新建一个sixaxis_control.yaml文件:
sixaxis:
# Publish all joint states -----------------------------------
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 50
# Position Controllers ---------------------------------------
joint1_position_controller:
type: effort_controllers/JointPositionController
joint: joint1
pid: {p: 100.0, i: 0.01, d: 10.0}
joint2_position_controller:
type: effort_controllers/JointPositionController
joint: joint2
pid: {p: 100.0, i: 0.01, d: 10.0}
joint3_position_controller:
type: effort_controllers/JointPositionController
joint: joint3
pid: {p: 100.0, i: 0.01, d: 10.0}
joint4_position_controller:
type: effort_controllers/JointPositionController
joint: joint4
pid: {p: 100.0, i: 0.01, d: 10.0}
joint5_position_controller:
type: effort_controllers/JointPositionController
joint: joint5
pid: {p: 100.0, i: 0.01, d: 10.0}
joint6_position_controller:
type: effort_controllers/JointPositionController
joint: joint6
pid: {p: 100.0, i: 0.01, d: 10.0}
注意, 这里如果之前选择的时PositionJointInterface, 那么type相应也要变为postition_controllers/JointPositionController.
在此之后我们只要写一个launch文件就好了! 在launch文件下下新建一个sixaxis_control.launch文件
内容如下:
<launch>
<rosparam file="$(find sixaxis_control)/config/sixaxis_control.yaml" command="load"/>
<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
output="screen" ns="/sixaxis" args="joint1_position_controller joint2_position_controller joint3_position_controller joint4_position_controller joint5_position_controller joint6_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="/sixaxis/joint_states" />
node>
launch>
全部都完成之后, 回到根目录下catkin_make一下(我也不是很清楚这一步是否必须, 不过make一下总没有坏处)
我们每一行都在一个新的终端当中执行如下命令:
roscore
roslaunch sixaxis_description gazebo.launch
roslaunch sixaxis_control sixaxis_control.launch
当我们在gazebo中看到我们的模型, 在执行sixaxis_control.launch的终端中看到如下的输出, 就说明我们大功告成了.
[INFO] [1582102023.557186, 0.000000]: Controller Spawner: Waiting for service controller_manager/load_controller
[INFO] [1582102023.587551, 0.000000]: Controller Spawner: Waiting for service controller_manager/switch_controller
[INFO] [1582102023.602375, 13.154000]: Controller Spawner: Waiting for service controller_manager/unload_controller
[INFO] [1582102023.621500, 13.162000]: Loading controller: joint1_position_controller
[INFO] [1582102023.680834, 13.183000]: Loading controller: joint2_position_controller
[INFO] [1582102023.703426, 13.185000]: Loading controller: joint3_position_controller
[INFO] [1582102023.732741, 13.203000]: Loading controller: joint4_position_controller
[INFO] [1582102023.752488, 13.211000]: Loading controller: joint5_position_controller
[INFO] [1582102023.781839, 13.219000]: Loading controller: joint6_position_controller
[INFO] [1582102023.806008, 13.223000]: Loading controller: joint_state_controller
[INFO] [1582102023.836477, 13.235000]: Controller Spawner: Loaded controllers: joint1_position_controller, joint2_position_controller, joint3_position_controller, joint4_position_controller, joint5_position_controller, joint6_position_controller, joint_state_controller
[INFO] [1582102023.851248, 13.239000]: Started controllers: joint1_position_controller, joint2_position_controller, joint3_position_controller, joint4_position_controller, joint5_position_controller, joint6_position_controller, joint_state_controller
如果当时选择的时EffortJointInterface, 在启动控制程序之前, 看到的模型很有可能是摊倒在地上. 但是打开了控制程序之后就会立起来了.(不过也不是特别有劲儿)
我们再打开一个终端, 输入
rosrun rqt_gui rqt_gui
点击plugin选择Topics下的Message Publisher
分别加入以下几个话题:
把所有的框都钩上, 然后展开任意一条栏目, 修改它的参数, 就可以看到机械臂跟着一起动起来啦!
如果需要对照最后的成果的话, 可以参考这个完整的工作空间.