ROS筆記-將自己的urdf導(dǎo)入rviz和gazebo-01
首先需要有一個(gè)正式的urdf文件,urdf文件可以通過(guò)手寫、三維建模軟件導(dǎo)出和機(jī)器人廠家直接給出等方式獲得,我這邊用的是實(shí)驗(yàn)室柔性協(xié)作機(jī)器人的urdf文件,從廠家那邊獲得,文件內(nèi)容如下圖所示

接下來(lái)開(kāi)始進(jìn)行導(dǎo)入
在~/catkin_ws/src 目錄下用catkin_create_pkg新建一個(gè)包,包名為testbot_descciption(可任意取名),依賴項(xiàng)目前是添加了urdf roscpp rospy sensor_msgs std_msgs tf 暫時(shí)來(lái)說(shuō)是夠用的,雖然我也不知道這些是不是必要的
接下來(lái)在testbot_description包內(nèi)新建幾個(gè)文件夾:config launch materials meshes rviz src urdf?
其中urdf文件夾用來(lái)放機(jī)器人的描述文件,即.urdf 或者.xacro
src文件夾用來(lái)放自己編寫的特定源碼
rviz文件夾用來(lái)存放 urdf.rviz 即機(jī)器人模型在rviz中的顯示,免得每次打開(kāi)rviz還要手動(dòng)添加robotmodel
meshes文件夾用來(lái)放urdf對(duì)應(yīng)的STL文件?
materials文件夾用來(lái)存放特定的urdf類的機(jī)器人描述文件
launch文件夾用來(lái)放相關(guān)的launch文件
config文件夾搭配launch文件來(lái)使用,其中會(huì)存放相關(guān)的配置文件用于ros與gazebo通信等功能
目前來(lái)說(shuō)較為關(guān)鍵的是urdf meshes launch config 這幾個(gè)文件夾

創(chuàng)建好對(duì)應(yīng)的文件夾后,首先將urdf文件存放到/testbot_description/urdf 文件夾中
將對(duì)應(yīng)的meshes存放到/testbot_description/meshes 文件夾中?
此時(shí)需要修改urdf文件中每個(gè)link子目錄下的geometry目錄中的filename路徑,將其修改為
filename="package://testbot_description/meshes/xxxx.STL"
然后這時(shí)候就可以通過(guò)相應(yīng)的launch文件使其在rviz中顯示出來(lái)了,對(duì)應(yīng)的launch文件如下所示
<launch>
?<!--send robot urdf to the "robot_description" parameter space-->
?<arg name="model" default="$(find testbot_description)/urdf/my_robot.xacro"/>
?<param name = "robot_description" command="$(find xacro)/xacro $(arg model)" />
?
?<!--launch the robot_state_publisher node and the joint_state_pulisher_gui node-->
?<node pkg="robot_state_publisher" type="robot_state_publisher" name="my_robot_state_pub" />
?<node pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" name="joint_state_publisher" />
?
?<!--launch the rviz and save the robot model as urdf.rviz-->
?<arg name="rvizconfig" default="$(find testbot_description)/rviz/urdf.rviz" />
?<node name="rviz" pkg="rviz" type="rviz" args="-d $(arg rvizconfig)" />
?
?</launch>
這個(gè)launch文件實(shí)現(xiàn)了三個(gè)功能
將urdf上傳到參數(shù)服務(wù)器的robot_description中
啟動(dòng)了兩個(gè)基本節(jié)點(diǎn),robot_state_publisher和joint_state_publisher?
啟動(dòng)了rviz 并且會(huì)將打開(kāi)的機(jī)器人模型保存為urdf.rviz
啟動(dòng)launch文件后會(huì)如下圖所示

注意:在launch前對(duì)testbot_description 文件夾中的CMakeList.txt文件進(jìn)行修改,將
install(DIRECTORY config launch urdf
? ? DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
)
添加進(jìn)去,以防出現(xiàn)問(wèn)題
此外,將urdf文件中的<robot name="XM3p"> 修改成
<robot name="XM3p" xmlns:xacro="http://www.ros.org/wiki/xacro">
將.urdf改成.xacro 這樣可以把urdf改成優(yōu)化的xacro文件,其中還有更多細(xì)節(jié)后面再說(shuō)

接下來(lái)是將機(jī)器人模型導(dǎo)入到gazebo中,這比在rviz中顯示相對(duì)來(lái)說(shuō)要復(fù)雜一點(diǎn),需要在config文件夾中配置.yaml文件,對(duì)原有的urdf文件(或xacro)進(jìn)行修改,添加一些gazebo需要的參數(shù),如每個(gè)非固定的關(guān)節(jié)joint添加<transmission></transmission>以及在末尾加上<gazebo></gazebo>等,具體的內(nèi)容可以參考wiki上針對(duì)urdf的教程,最后將launch文件修改為
<launch>
?<!--send robot urdf to the "robot_description" parameter space-->
?<arg name="model" default="$(find testbot_description)/urdf/my_robot.xacro"/>
?<param name = "robot_description" command="$(find xacro)/xacro $(arg model)" />
?
?<!--launch the robot_state_publisher node and the joint_state_pulisher_gui node-->
?<node pkg="robot_state_publisher" type="robot_state_publisher" name="my_robot_state_pub" />
?<node pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" name="joint_state_publisher" />
?
?<!--launch the rviz and save the robot model as urdf.rviz-->
?<arg name="rvizconfig" default="$(find testbot_description)/rviz/urdf.rviz" />
?<node name="rviz" pkg="rviz" type="rviz" args="-d $(arg rvizconfig)" />
?
?
?<!--some argument about gazebo -->
?<arg name="paused" default="false"/>
?<arg name="use_sim_time" default="true"/>
?<arg name="gui" default="true"/>
?<arg name="headless" default="false"/>
?<arg name="debug" default="false"/>
?<include file="$(find gazebo_ros)/launch/empty_world.launch">
? ?<arg name="debug" value="$(arg debug)" />
? ?<arg name="gui" value="$(arg gui)" />
? ?<arg name="paused" value="$(arg paused)"/>
? ?<arg name="use_sim_time" value="$(arg use_sim_time)"/>
? ?<arg name="headless" value="$(arg headless)"/>
?</include>
?
?<!-- spawn robot model in gazebo world -->
?<node pkg="gazebo_ros" type="spawn_model" name="urdf_spawner"
? ? ? ?args="-z 1.0 -unpause -urdf -model robot -param robot_description" respawn="false" output="screen" />
?
?<!-- load the joints.yaml file into XM3p_joint_state_controller namespace for gazebo --> ? ? ?
?<rosparam command="load"
? ? ? ? ? ?file="$(find testbot_description)/config/joints.yaml"
? ? ? ? ? ?ns="XM3p_joint_state_controller" />
?
?<!-- load the each_joint.yaml file into namespace to controll the position of each joints --> ? ? ? ?
?<rosparam command="load"
? ? ? ? ? ?file="$(find testbot_description)/config/each_joints.yaml"
? ? ? ? ? ?ns="XM3p_joint_position_controller" />
<!-- load the .yaml file into namespace to controll the position of group joints --> ? ? ? ?
?<rosparam command="load"
? ? ? ? ? ?file="$(find testbot_description)/config/group_joints_control.yaml"
? ? ? ? ? ?ns="XM3p_group_joint_position_controller" />
? ? ? ? ? ?
?<node name="XM3p_controller_spawner" pkg="controller_manager" type="spawner"
? ?args="XM3p_joint_state_controller
? ? ? ? ?XM3p_joint_position_controller
? ? ? ? ?XM3p_group_joint_position_controller
? ? ? ? ?--shutdown-timeout 3"/>
</launch>
獲得的效果為

目前的進(jìn)度:在gazebo中能生成我所導(dǎo)入的urdf文件,并且可以通過(guò)rostopic pub 指令來(lái)發(fā)送控制指令控制機(jī)械臂的關(guān)節(jié)轉(zhuǎn)動(dòng)
下一步要解決的問(wèn)題:
機(jī)械臂在gazebo的empty.world中并不是固定在地面上的
相機(jī)模型的導(dǎo)入
完善仿真環(huán)境