这里的turtlebot是使用源码安装的,如果是终端使用命令安装的对应修改以下路径中的文件:
/opt/ros/kinetic/share
一、添加kobuki_hexagons_hokuyo.urdf.xacro
cd ~/turtlebot/src/turtlebot/turtlebot_description/robots
gedit kobuki_hexagons_hokuyo.urdf.xacro
复制kobuki_hexagons_kinect.urdf.xacro中的内容并修改
<?xml version="1.0"?>
<!--
- Base : kobuki
- Stacks : hexagons
- 3d Sensor : hokuyo
-->
<robot name="turtlebot" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:include filename="$(find turtlebot_description)/urdf/turtlebot_library.urdf.xacro" />
<xacro:include filename="$(find kobuki_description)/urdf/kobuki.urdf.xacro" />
<xacro:include filename="$(find turtlebot_description)/urdf/stacks/hexagons.urdf.xacro"/>
<!--(修改这里,将kinect改为hokuyo)-->
<xacro:include filename="$(find turtlebot_description)/urdf/sensors/hokuyo.urdf.xacro"/>
<kobuki/>
<stack_hexagons parent="base_link"/>
<!--(修改这里,将kinect改为hokuyo)-->
<sensor_hokuyo parent="base_link"/>
</robot>
二、修改turtlebot_common_library.urdf.xacro
cd ~/turtlebot/src/turtlebot/turtlebot_description/urdf
gedit turtlebot_common_library.urdf.xacro
在此文件中增加内容
<?xml version="1.0"?>
<!--
The complete turtlebot library of xacros for easy reference
-->
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<!-- General -->
<xacro:include filename="$(find turtlebot_description)/urdf/common_properties.urdf.xacro"/>
<xacro:include filename="$(find turtlebot_description)/urdf/turtlebot_properties.urdf.xacro"/>
<!--(添加一行)-->
<xacro:include filename="$(find turtlebot_description)/urdf/sensors/hokuyo.urdf.xacro"/>
</robot>
三、添加hokuyo.urdf.xacro文件
cd ~/turtlebot/src/turtlebot/turtlebot_description/urdf/sensors
gedit hokuyo.urdf.xacro
<?xml version="1.0"?>
<!-- script_version=1.1 -->
<robot name="sensor_hokuyo" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:include filename="$(find turtlebot_description)/urdf/turtlebot_gazebo.urdf.xacro"/>
<xacro:include filename="$(find turtlebot_description)/urdf/turtlebot_properties.urdf.xacro"/>
<!-- Hokuyo 2D LIDAR -->
<xacro:macro name="sensor_hokuyo" params="parent">
<joint name="laser" type="fixed">
<!--(此处修改激光雷达摆放位置)-->
<origin xyz="0.0 0 0.3742" rpy="0 0.0 0.0" />
<parent link="base_link" />
<child link="hokuyo_link" />
</joint>
<!-- Hokuyo Laser -->
<link name="hokuyo_link">
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.1 0.1 0.1"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://turtlebot_description/meshes/sensors/hokuyo.dae"/>
</geometry>
</visual>
<inertial>
<mass value="1e-5" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
</inertial>
</link>
<!-- Set up laser gazebo details -->
<turtlebot_sim_2dsensor/>
</xacro:macro>
</robot>
四、下载hokuyo模型
参照gazebo官网教程下载hokuyo.dae模型包:网址
cd ~/.gazebo/models
wget -q -R *index.html*,*.tar.gz --no-parent -r -x -nH http://models.gazebosim.org/hokuyo/
cd ~/.gazebo/models/hokuyo/meshes
cp hokuyo_convex.stl ~/turtlebot/src/turtlebot/turtlebot_description/meshes/sensors
cp hokuyo.dae ~/turtlebot/src/turtlebot/turtlebot_description/meshes/sensors
五、为turtlebot_gazebo.urdf.xacro添加lidar
型号:URG-04LX 参数:扫描范围:240°、测量距离:0.06-5.6m、角度分辨率:0.36°、测量精度:0.03m
cd ~/turtlebot/src/turtlebot/turtlebot_description/urdf
gedit turtlebot_gazebo.urdf.xacro
<?xml version="1.0"?>
<robot name="turtlebot_gazebo" xmlns:xacro="http://ros.org/wiki/xacro">
<!-- Microsoft Kinect / ASUS Xtion PRO Live for simulation -->
<!--(把摄像头注释掉)-->
<!--<xacro:macro name="turtlebot_sim_3dsensor">
<gazebo reference="camera_link">
<sensor type="depth" name="camera">
<always_on>true</always_on>
<update_rate>20.0</update_rate>
<camera>
<horizontal_fov>${60.0*M_PI/180.0}</horizontal_fov>
<image>
<format>B8G8R8</format>
<width>640</width>
<height>480</height>
</image>
<clip>
<near>0.05</near>
<far>8.0</far>
</clip>
</camera>
<plugin name="kinect_camera_controller" filename="libgazebo_ros_openni_kinect.so">
<cameraName>camera</cameraName>
<alwaysOn>true</alwaysOn>
<updateRate>10</updateRate>
<imageTopicName>rgb/image_raw</imageTopicName>
<depthImageTopicName>depth/image_raw</depthImageTopicName>
<pointCloudTopicName>depth/points</pointCloudTopicName>
<cameraInfoTopicName>rgb/camera_info</cameraInfoTopicName>
<depthImageCameraInfoTopicName>depth/camera_info</depthImageCameraInfoTopicName>
<frameName>camera_depth_optical_frame</frameName>
<baseline>0.1</baseline>
<distortion_k1>0.0</distortion_k1>
<distortion_k2>0.0</distortion_k2>
<distortion_k3>0.0</distortion_k3>
<distortion_t1>0.0</distortion_t1>
<distortion_t2>0.0</distortion_t2>
<pointCloudCutoff>0.4</pointCloudCutoff>
</plugin>
</sensor>
</gazebo>
</xacro:macro>-->
<!--(添加lidar)-->
<xacro:macro name="turtlebot_sim_2dsensor">
<gazebo reference="hokuyo_link">
<sensor type="ray" name="head_hokuyo_sensor">
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<update_rate>40</update_rate>
<ray>
<scan>
<horizontal>
<samples>720</samples>
<resolution>0.36</resolution>
<min_angle>-1.047198</min_angle>
<max_angle>1.047198</max_angle>
</horizontal>
</scan>
<range>
<min>0.06</min>
<max>5.6</max>
<resolution>0.03</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_laser.so">
<!--topicName>/turtlebot/laser/scan</topicName-->
<topicName>scan</topicName>
<frameName>hokuyo_link</frameName>
</plugin>
</sensor>
</gazebo>
</xacro:macro>
</robot>
六、修改hexagons.urdf.xacro
这个是turtlebot底盘的模型,由于不用kinect,所以把多余的部分去掉
cd ~/turtlebot/src/turtlebot/turtlebot_description/urdf/stacks
gedit hexagons.urdf.xacro
<?xml version="1.0"?>
<!--
Hexagon stacks
-->
<robot name="stack_hexagons" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:include filename="$(find turtlebot_description)/urdf/common_properties.urdf.xacro"/>
<!-- Xacro properties -->
<xacro:property name="M_SCALE" value="0.001"/>
<!-- Xacro macros -->
<!-- Pole macros -->
<xacro:macro name="stack_bottom_pole" params="parent number x_loc y_loc z_loc">
<joint name="pole_bottom_${number}_joint" type="fixed">
<origin xyz="${x_loc} ${y_loc} ${z_loc}" rpy="0 0 0"/>
<parent link="${parent}"/>
<child link="pole_bottom_${number}_link"/>
</joint>
<link name="pole_bottom_${number}_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://turtlebot_description/meshes/stacks/hexagons/pole_bottom.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder length="0.0492" radius="0.006"/>
</geometry>
</collision>
<inertial>
<mass value="0.008"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="0.000001686" ixy="0.0" ixz="0.0"
iyy="0.000001686" iyz="0.0"
izz="0.000000144"/>
</inertial>
</link>
</xacro:macro>
<!--(把中间的支架和平台去掉)-->
<!--<xacro:macro name="stack_middle_pole" params="parent number x_loc y_loc z_loc">
<joint name="pole_middle_${number}_joint" type="fixed">
<origin xyz="${x_loc} ${y_loc} ${z_loc}" rpy="0 0 0" />
<parent link="${parent}"/>
<child link="pole_middle_${number}_link"/>
</joint>
<link name="pole_middle_${number}_link">
<visual>
<origin xyz="0 0 0" rpy="0 ${M_PI} 0"/>
<geometry>
<mesh filename="package://turtlebot_description/meshes/stacks/hexagons/pole_middle.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder length="0.0608" radius="0.006"/>
</geometry>
</collision>
<inertial>
<mass value="0.012"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.000003805" ixy="0.0" ixz="0.0"
iyy="0.000003805" iyz="0.0"
izz="0.000000216"/>
</inertial>
</link>
</xacro:macro>-->
<xacro:macro name="stack_top_pole" params="parent number x_loc y_loc z_loc">
<joint name="pole_top_${number}_joint" type="fixed">
<origin xyz="${x_loc} ${y_loc} ${z_loc}" rpy="0 0 0"/>
<parent link="${parent}"/>
<child link="pole_top_${number}_link"/>
</joint>
<link name="pole_top_${number}_link">
<visual>
<origin xyz=" 0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://turtlebot_description/meshes/stacks/hexagons/pole_top.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder length="0.2032" radius="0.006"/>
</geometry>
</collision>
<inertial>
<mass value="0.060"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.000206991" ixy="0.0" ixz="0.0"
iyy="0.000206991" iyz="0.0"
izz="0.000001080"/>
</inertial>
</link>
</xacro:macro>
<!--(把安装kinect的支架去掉)-->
<!--<xacro:macro name="stack_3d_sensor_pole" params="parent number x_loc y_loc z_loc">
<joint name="pole_kinect_${number}_joint" type="fixed">
<origin xyz="${x_loc} ${y_loc} ${z_loc}" rpy="0 0 0"/>
<parent link="${parent}"/>
<child link="pole_kinect_${number}_link"/>
</joint>
<link name="pole_kinect_${number}_link">
<visual>
<origin xyz="0 0 -0.01" rpy="0 0 0"/>
<geometry>
<mesh filename="package://turtlebot_description/meshes/sensors/sensor_pole.dae" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder length="0.0936" radius="0.006"/>
</geometry>
</collision>
<inertial>
<mass value="0.020"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.000014782" ixy="0.0" ixz="0.0"
iyy="0.000014782" iyz="0.0"
izz="0.000000360"/>
</inertial>
</link>
</xacro:macro>-->
<!--
Stack macro - all the components relative transforms are made with respect
to the parent link (usually base_link). They could be made relative to each
other, but there is no necessary reason to do so.
-->
<xacro:macro name="stack_hexagons" params="parent">
<stack_bottom_pole parent="${parent}" number="0" x_loc= "0.120" y_loc= "0.082" z_loc="0.1028"/>
<stack_bottom_pole parent="${parent}" number="1" x_loc= "0.055" y_loc= "0.120" z_loc="0.1028"/>
<stack_bottom_pole parent="${parent}" number="2" x_loc="-0.055" y_loc= "0.120" z_loc="0.1028"/>
<stack_bottom_pole parent="${parent}" number="3" x_loc= "0.120" y_loc="-0.082" z_loc="0.1028"/>
<stack_bottom_pole parent="${parent}" number="4" x_loc= "0.055" y_loc="-0.120" z_loc="0.1028"/>
<stack_bottom_pole parent="${parent}" number="5" x_loc="-0.055" y_loc="-0.120" z_loc="0.1028"/>
<joint name="plate_bottom_joint" type="fixed">
<origin xyz="0.02364 0.0 0.1306" rpy="0 0 0"/>
<parent link="${parent}"/>
<child link="plate_bottom_link"/>
</joint>
<link name="plate_bottom_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://turtlebot_description/meshes/stacks/hexagons/plate_bottom.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="-0.02364 0 0" rpy="0 0 0"/>
<geometry>
<cylinder length="0.006" radius="0.170"/>
</geometry>
</collision>
<inertial>
<mass value="0.520" />
<origin xyz="0 0 0" />
<inertia ixx="0.003328" ixy="0.0" ixz="0.0"
iyy="0.003328" iyz="0.0"
izz="0.006656" />
</inertial>
</link>
<!--(把中间的支架和平台去掉)-->
<!--<stack_middle_pole parent="${parent}" number="0" x_loc= "0.0381" y_loc= "0.1505" z_loc="0.1640"/>
<stack_middle_pole parent="${parent}" number="1" x_loc= "0.0381" y_loc="-0.1505" z_loc="0.1640"/>
<stack_middle_pole parent="${parent}" number="2" x_loc="-0.0381" y_loc= "0.1505" z_loc="0.1640"/>
<stack_middle_pole parent="${parent}" number="3" x_loc="-0.0381" y_loc="-0.1505" z_loc="0.1640"/>
<joint name="plate_middle_joint" type="fixed">
<origin xyz="-0.01364 0.0 0.1874" rpy="0 0 0"/>
<parent link="${parent}"/>
<child link="plate_middle_link"/>
</joint>
<link name="plate_middle_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://turtlebot_description/meshes/stacks/hexagons/plate_middle.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0.01364 0.0 0.0" rpy="0 0 0"/>
<geometry>
<cylinder length="0.006" radius="0.170"/>
</geometry>
</collision>
<inertial>
<mass value="0.520" />
<origin xyz="0 0 0" />
<inertia ixx="0.003328" ixy="0.0" ixz="0.0"
iyy="0.003328" iyz="0.0"
izz="0.006656" />
</inertial>
</link>-->
<!--(把顶部的支架和平台下移0.0608即中间支架的高度)-->
<stack_top_pole parent="${parent}" number="0" x_loc= "0.0381" y_loc= "0.1505" z_loc="0.2312"/>
<stack_top_pole parent="${parent}" number="1" x_loc= "0.0381" y_loc="-0.1505" z_loc="0.2312"/>
<stack_top_pole parent="${parent}" number="2" x_loc="-0.0381" y_loc= "0.1505" z_loc="0.2312"/>
<stack_top_pole parent="${parent}" number="3" x_loc="-0.0381" y_loc="-0.1505" z_loc="0.2312"/>
<!--(把安装kinect的支架去掉)-->
<!--<stack_3d_sensor_pole parent="${parent}" number="0" x_loc="-0.1024" y_loc= "0.098" z_loc="0.2372"/>
<stack_3d_sensor_pole parent="${parent}" number="1" x_loc="-0.1024" y_loc="-0.098" z_loc="0.2372"/>-->
<joint name="plate_top_joint" type="fixed">
<origin xyz="-0.01364 0.0 0.3358" rpy="0 0 0"/>
<parent link="${parent}"/>
<child link="plate_top_link"/>
</joint>
<link name="plate_top_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://turtlebot_description/meshes/stacks/hexagons/plate_top.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0.01364 0 0" rpy="0 0 0"/>
<geometry>
<cylinder length="0.006" radius="0.170"/>
</geometry>
</collision>
<inertial>
<mass value="0.520"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.003328" ixy="0.0" ixz="0.0"
iyy="0.003328" iyz="0.0"
izz="0.006656" />
</inertial>
</link>
</xacro:macro>
</robot>
效果图:
七、修改环境变量
gedit ~/.bashrc
添加内容
export TURTLEBOT_BASE=kobuki
export TURTLEBOT_STACKS=hexagons
export TURTLEBOT_3D_SENSOR=hokuyo