因為都是一邊學一邊做,所以難免走一些彎路了,如果有什么錯誤希望各位指出來,謝謝
接着上次的思路,希望讓添加的模型動起來,但連Gazebo官網上都是用urdf文件講的……所以那還是用urdf文件吧
通過前面我們已經知道怎么讓urdf文件形成的模型在gazebo里出現了(在launch文件中spawn一個),這一次希望它能動起來,基於一輛簡單的“小車”模型吧,參考的這個項目以及官方教程。這個文件是已經完成的,還是從僅有模型形態的urdf文件開始,一步步來:
1. 添加<transmission>標簽
這一步比較簡單,就是需要在urdf文件的<robot>標簽下添加與joint相應的<transimission>標簽。
這個標簽的作用是在joint上添加一個actuator(執行器),也很好理解,大致形式如下:
<transmission name="tran_SOME_JOINT"> <type>transmission_interface_SimpleTransmission</type> <joint name="SOME_JOINT"> <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface> </joint> <actuator name="ACTUATOR"> <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface> <mechanicalReduction>1</mechanicalReduction> </actuator> </transmission>
可以看到主要就是三部分的內容:type, joint和actuator
<type>表示transmission的類型
<joint>指明將在哪個joint上添加執行器,用name給出該joint的名字。另外,其中還包含一個<hardwareInterface>標簽,用來指定一個支持的關節空間硬件接口。這句話是官方翻譯過來的,感覺等於白說,還沒仔細研究,不是很懂hardInterface是干啥的,留個坑
<actuator>表示連接到joint的執行器,name表示它的名字。包含<mechanicalReduction>表示減速比。
- 來自官方的幾個說明:
- 如果在Gazebo里加載這個transmission,<joint>里的<hardwareInterface>的值應該是EffortJointInterface,而如果在RobotHW中加載,則該值應該是haedwareInterface/EffortJointInterface(當然不僅有EffortJointInterface,還有VelocityJointInterface, PositionJointInterface,或者自己寫的類);
- <actuator>標簽下的<mechanicalReduction>是可選項,而<hardwareInterface>在ROS Kinetic版本以后就不在這里出現了,而是在<joint>標簽里,這個應該是一個bug,所以Gazebo官方里要求兩個地方都寫,不過我也在Kinetic中測試過,去掉之后也可以運行。
到此為止,相當於是模型部分弄完了,加的transimission也算是實際機器人的硬件部分,所以我就暫時把這以前的內容視為一大部分,接下來就是控制器部分,相當於軟件部分。雖說我把以后的工作與前面分開來,但並不代表不再對urdf文件進行操作了,只是說從功能的上,我個人覺得這樣划分更易於理解。
2. 添加gazebo_ros_control plugin
ROS里有個ros_control包,用於機器人的控制,相應的,在Gazebo里使用則需要在urdf文件中添加一個gazebo plugin:
<gazebo> <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so"> <robotNamespace>/MYROBOT</robotNamespace> </plugin> </gazebo>
默認使用這樣就夠了,但是我在運行的時候遇到了一個關於什么legacyNS的報錯,查了一下,需要在<plugin>里面添加一條:
<legacyModeNS>true</legacyModeNS>
3. 新建一個ros_controls包
新建一個新ROS包
mkdir ~/catkin_ws cd ~/catkin_ws catkin_create_pkg MYROBOT_control controller_manager joint_state_controller robot_state_publisher cd MYROBOT_control mkdir config mkdir launch
新建.yaml配置文件
.yaml文件用於配置控制器的類型和PID參數(為啥一定是PID控制器?),MYROBOT_control大概長這樣:
MYROBOT: # controls the rear two tires based on individual motors # Publish all joint states ----------------------------------- joint_state_controller: type: joint_state_controller/JointStateController publish_rate: 50 # Controllers ----------------------------------- SOME_JOINT_controller: type: velocity_controllers/JointVelocityController joint: SOME_JOINT pid: {p: 100.0, i: 0.01, d: 10.0} ANOTHER_JOINT_controller: type: effort_controllers/JointPositionController joint: ANOTHER_JOINT pid: {p: 100.0, i: 0.01, d: 10.0}
這里要注意controller的type,要和transimission中的hardwareInterface類型相對應。
在launch文件中添加controller節點啟動語句
這里主要是為了加載.yaml文件,以及啟動controller的spawn節點,網上的帖子大部分是另外寫了一個launch文件,我是直接寫在之前我們啟動機器人的launch文件中了,也是可以的:
<!-- Load joint controller configurations from YAML file to parameter server --> <rosparam file="$(find MYROBOT_control)/config/MYROBOT_control.yaml" command="load"/> <!-- load controllers --> <node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" ns="/MYROBOT" args="joint_state_controller SOME_JOINT_controller ANOTHER_JOINT_controller"/>
注意SOME_JOINT_controller等對應着MYROBOT_control.yaml里的SOME_JOINT_controller等名字。
至此,所有的文件和內容都准備好了,通過roslaunch啟動以上launch文件,就可以看到小車出現在gazebo的世界中了,這時候通過rostopic list可以看到以下topics,比原來多了關於controller的topics
/clock /gazebo/link_states /gazebo/model_states /gazebo/parameter_descriptions /gazebo/parameter_updates /gazebo/set_link_state /gazebo/set_model_state /gazebo_gui/parameter_descriptions /gazebo_gui/parameter_updates /rosout /rosout_agg /MYROBOT/joint_states /MYROBOT/SOME_JOINT_controller/command /MYROBOT/ANOTHER_JOINT_controller/command
通過rostopic pub向controller發送指令
rostopic pub -r 10 /MYROBOT/SOME_JOINT_controller/command std_msgs/Float64 "data: 100.0"
因為我這邊是用的一輛小車,joint是小車的輪子,這時候發現小車並沒有動,或只是動了一下,但其實在Gazebo中選定那個輪子發現他其實是在轉動的,所以就是說它在空轉…這是因為在urdf文件中沒有添加輪子的摩擦力標簽,其默認是1。所以需要在urdf中添加以下標簽,告訴Gazebo輪子的摩擦系數。由此可以看出,Gazebo作為一個物理仿真軟件,一切都是物理定理驅動的。
<gazebo reference="rear_right_wheel_link"> <mu1>10000000</mu1> <mu2>10000000</mu2> <kp>10000000</kp> <kd>1</kd> </gazebo> <gazebo reference="rear_left_wheel_link"> <mu1>10000000</mu1> <mu2>10000000</mu2> <kp>10000000</kp> <kd>1</kd> </gazebo>
其中mu1和mu2表示其摩擦系數,kp和kd表示其剛性,具體參見關於<gazebo>標簽的說明。
重新啟動,在pub一下就可以看到小車瘋狂轉圈了~但是由於4個輪子還沒有協同控制,小車跑起來怪怪的。
至此,ros已經和gazebo連起來了,我們也可以用ros給gazebo里面的機器人發布命令了,散花。