目录
my_base_camera_laser.urdf.xacro
文件目录结构
catkin_ws/
├── src
├── car
├── CMakeLists.txt
├── launch
├── mainpage.dox
├── mainfest.xml
├── Makefile
├── urdf
└── xacro
└── .....
└── world
└── my.world
└── car_slam
├── CMakeLists.txt
├── config
└── .....
├── launch
├── mainpage.dox
├── mainfest.xml
├── Makefile
├── map
└── .....
└── param
├── base_local_planner_params.yaml
├── costmap_common_params.yaml
├── global_costmap_params.yaml
└── local_costmap_params.yaml
1 仿真
创建功能包
catkin_ws $ source devel/setup.sh
catkin_ws/src $ roscreate-pkg car urdf xacro gazebo_ros gazebo_ros_control gazebo_plugins
mkdir -p launch urdf/xacro wrold
构建小车的代码文件放在 urdf/xacro 下 ,launch 存放启动文件, world 存放地图文件
move.urdf.xacro
<robot name="my_car_move" xmlns:xacro="http://wiki.ros.org/xacro">
<!-- 传动实现:用于连接控制器与关节 -->
<xacro:macro name="joint_trans" params="joint_name">
<!-- Transmission is important to link the joints and the controller -->
<transmission name="${joint_name}_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${joint_name}">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
<actuator name="${joint_name}_motor">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</xacro:macro><!-- 每一个驱动轮都需要配置传动装置 -->
<xacro:joint_trans joint_name="left_wheel2base_link" />
<xacro:joint_trans joint_name="right_wheel2base_link" /><!-- 控制器 -->
<gazebo>
<plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
<rosDebugLevel>Debug</rosDebugLevel>
<publishWheelTF>true</publishWheelTF>
<robotNamespace>/</robotNamespace>
<publishTf>1</publishTf>
<publishWheelJointState>true</publishWheelJointState>
<alwaysOn>true</alwaysOn>
<updateRate>100.0</updateRate>
<legacyMode>true</legacyMode>
<leftJoint>left_wheel2base_link</leftJoint> <!-- 左轮 -->
<rightJoint>right_wheel2base_link</rightJoint> <!-- 右轮 -->
<wheelSeparation>${base_link_radius * 2}</wheelSeparation> <!-- 车轮间距 -->
<wheelDiameter>${wheel_radius * 2}</wheelDiameter> <!-- 车轮直径 -->
<broadcastTF>1</broadcastTF>
<wheelTorque>30</wheelTorque>
<wheelAcceleration>1.8</wheelAcceleration>
<commandTopic>cmd_vel</commandTopic> <!-- 运动控制话题 -->
<odometryFrame>odom</odometryFrame>
<odometryTopic>odom</odometryTopic> <!-- 里程计话题 -->
<robotBaseFrame>base_footprint</robotBaseFrame> <!-- 根坐标系 -->
</plugin>
</gazebo></robot>
my_base.urdf.xacro
<!--
使用 xacro 优化 URDF 版的小车底盘实现:实现思路:
1.将一些常量、变量封装为 xacro:property
比如:PI 值、小车底盘半径、离地间距、车轮半径、宽度 ....
2.使用 宏 封装驱动轮以及支撑轮实现,调用相关宏生成驱动轮与支撑轮-->
<!-- 根标签,必须声明 xmlns:xacro -->
<robot name="my_base" xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- 封装变量、常量 -->
<!-- PI 值设置精度需要高一些,否则后续车轮翻转量计算时,可能会出现肉眼不能察觉的车轮倾斜,从而导致模型抖动 -->
<xacro:property name="PI" value="3.1415926"/>
<!-- 宏:黑色设置 -->
<material name="black">
<color rgba="0.0 0.0 0.0 1.0" />
</material>
<!-- 底盘属性 -->
<xacro:property name="base_footprint_radius" value="0.001" /> <!-- base_footprint 半径 -->
<xacro:property name="base_link_radius" value="0.1" /> <!-- base_link 半径 -->
<xacro:property name="base_link_length" value="0.08" /> <!-- base_link 长 -->
<xacro:property name="earth_space" value="0.015" /> <!-- 离地间距 -->
<xacro:property name="base_link_m" value="0.5" /> <!-- 质量 --><!-- 底盘 -->
<link name="base_footprint">
<visual>
<geometry>
<sphere radius="${base_footprint_radius}" />
</geometry>
</visual>
</link><link name="base_link">
<visual>
<geometry>
<cylinder radius="${base_link_radius}" length="${base_link_length}" />
</geometry>
<origin xyz="0 0 0" rpy="0 0 0" />
<material name="yellow">
<color rgba="0.5 0.3 0.0 0.5" />
</material>
</visual>
<collision>
<geometry>
<cylinder radius="${base_link_radius}" length="${base_link_length}" />
</geometry>
<origin xyz="0 0 0" rpy="0 0 0" />
</collision>
<xacro:cylinder_inertial_matrix m="${base_link_m}" r="${base_link_radius}" h="${base_link_length}" /></link>
<joint name="base_link2base_footprint" type="fixed">
<parent link="base_footprint" />
<child link="base_link" />
<origin xyz="0 0 ${earth_space + base_link_length / 2 }" />
</joint>
<gazebo reference="base_link">
<material>Gazebo/Yellow</material>
</gazebo><!-- 驱动轮 -->
<!-- 驱动轮属性 -->
<xacro:property name="wheel_radius" value="0.0325" /><!-- 半径 -->
<xacro:property name="wheel_length" value="0.015" /><!-- 宽度 -->
<xacro:property name="wheel_m" value="0.05" /> <!-- 质量 --><!-- 驱动轮宏实现 -->
<xacro:macro name="add_wheels" params="name flag">
<link name="${name}_wheel">
<visual>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_length}" />
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="${PI / 2} 0.0 0.0" />
<material name="black" />
</visual>
<collision>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_length}" />
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="${PI / 2} 0.0 0.0" />
</collision>
<xacro:cylinder_inertial_matrix m="${wheel_m}" r="${wheel_radius}" h="${wheel_length}" /></link>
<joint name="${name}_wheel2base_link" type="continuous">
<parent link="base_link" />
<child link="${name}_wheel" />
<origin xyz="0 ${flag * base_link_radius} ${-(earth_space + base_link_length / 2 - wheel_radius) }" />
<axis xyz="0 1 0" />
</joint><gazebo reference="${name}_wheel">
<material>Gazebo/Red</material>
</gazebo></xacro:macro>
<xacro:add_wheels name="left" flag="1" />
<xacro:add_wheels name="right" flag="-1" />
<!-- 支撑轮 -->
<!-- 支撑轮属性 -->
<xacro:property name="support_wheel_radius" value="0.0075" /> <!-- 支撑轮半径 -->
<xacro:property name="support_wheel_m" value="0.03" /> <!-- 质量 --><!-- 支撑轮宏 -->
<xacro:macro name="add_support_wheel" params="name flag" >
<link name="${name}_wheel">
<visual>
<geometry>
<sphere radius="${support_wheel_radius}" />
</geometry>
<origin xyz="0 0 0" rpy="0 0 0" />
<material name="black" />
</visual>
<collision>
<geometry>
<sphere radius="${support_wheel_radius}" />
</geometry>
<origin xyz="0 0 0" rpy="0 0 0" />
</collision>
<xacro:sphere_inertial_matrix m="${support_wheel_m}" r="${support_wheel_radius}" />
</link><joint name="${name}_wheel2base_link" type="continuous">
<parent link="base_link" />
<child link="${name}_wheel" />
<origin xyz="${flag * (base_link_radius - support_wheel_radius)} 0 ${-(base_link_length / 2 + earth_space / 2)}" />
<axis xyz="1 1 1" />
</joint>
<gazebo reference="${name}_wheel">
<material>Gazebo/Red</material>
</gazebo>
</xacro:macro><xacro:add_support_wheel name="front" flag="1" />
<xacro:add_support_wheel name="back" flag="-1" />
</robot>
my_laser.urdf.xacro
<!--
小车底盘添加雷达
-->
<robot name="my_laser" xmlns:xacro="http://wiki.ros.org/xacro"><!-- 雷达支架 -->
<xacro:property name="support_length" value="0.15" /> <!-- 支架长度 -->
<xacro:property name="support_radius" value="0.01" /> <!-- 支架半径 -->
<xacro:property name="support_x" value="0.0" /> <!-- 支架安装的x坐标 -->
<xacro:property name="support_y" value="0.0" /> <!-- 支架安装的y坐标 -->
<xacro:property name="support_z" value="${base_link_length / 2 + support_length / 2}" /> <!-- 支架安装的z坐标:底盘高度 / 2 + 支架高度 / 2 --><xacro:property name="support_m" value="0.02" /> <!-- 支架质量 -->
<link name="support">
<visual>
<geometry>
<cylinder radius="${support_radius}" length="${support_length}" />
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
<material name="red">
<color rgba="0.8 0.2 0.0 0.8" />
</material>
</visual><collision>
<geometry>
<cylinder radius="${support_radius}" length="${support_length}" />
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
</collision><xacro:cylinder_inertial_matrix m="${support_m}" r="${support_radius}" h="${support_length}" />
</link>
<joint name="support2base_link" type="fixed">
<parent link="base_link" />
<child link="support" />
<origin xyz="${support_x} ${support_y} ${support_z}" />
</joint><gazebo reference="support">
<material>Gazebo/White</material>
</gazebo><!-- 雷达属性 -->
<xacro:property name="laser_length" value="0.05" /> <!-- 雷达长度 -->
<xacro:property name="laser_radius" value="0.03" /> <!-- 雷达半径 -->
<xacro:property name="laser_x" value="0.0" /> <!-- 雷达安装的x坐标 -->
<xacro:property name="laser_y" value="0.0" /> <!-- 雷达安装的y坐标 -->
<xacro:property name="laser_z" value="${support_length / 2 + laser_length / 2}" /> <!-- 雷达安装的z坐标:支架高度 / 2 + 雷达高度 / 2 --><xacro:property name="laser_m" value="0.1" /> <!-- 雷达质量 -->
<!-- 雷达关节以及link -->
<link name="laser">
<visual>
<geometry>
<cylinder radius="${laser_radius}" length="${laser_length}" />
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
<material name="black" />
</visual>
<collision>
<geometry>
<cylinder radius="${laser_radius}" length="${laser_length}" />
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
</collision>
<xacro:cylinder_inertial_matrix m="${laser_m}" r="${laser_radius}" h="${laser_length}" />
</link><joint name="laser2support" type="fixed">
<parent link="support" />
<child link="laser" />
<origin xyz="${laser_x} ${laser_y} ${laser_z}" />
</joint>
<gazebo reference="laser">
<material>Gazebo/Black</material>
</gazebo>
</robot>
my_head.urdf.xacro
<robot name="base" xmlns:xacro="http://wiki.ros.org/xacro">
<!-- Macro for inertia matrix -->
<xacro:macro name="sphere_inertial_matrix" params="m r">
<inertial>
<mass value="${m}" />
<inertia ixx="${2*m*r*r/5}" ixy="0" ixz="0"
iyy="${2*m*r*r/5}" iyz="0"
izz="${2*m*r*r/5}" />
</inertial>
</xacro:macro><xacro:macro name="cylinder_inertial_matrix" params="m r h">
<inertial>
<mass value="${m}" />
<inertia ixx="${m*(3*r*r+h*h)/12}" ixy = "0" ixz = "0"
iyy="${m*(3*r*r+h*h)/12}" iyz = "0"
izz="${m*r*r/2}" />
</inertial>
</xacro:macro><xacro:macro name="Box_inertial_matrix" params="m l w h">
<inertial>
<mass value="${m}" />
<inertia ixx="${m*(h*h + l*l)/12}" ixy = "0" ixz = "0"
iyy="${m*(w*w + l*l)/12}" iyz= "0"
izz="${m*(w*w + h*h)/12}" />
</inertial>
</xacro:macro>
</robot>
my_camera.urdf.xacro
<!-- 摄像头相关的 xacro 文件 -->
<robot name="my_camera" xmlns:xacro="http://wiki.ros.org/xacro">
<!-- 摄像头属性 -->
<xacro:property name="camera_length" value="0.01" /> <!-- 摄像头长度(x) -->
<xacro:property name="camera_width" value="0.025" /> <!-- 摄像头宽度(y) -->
<xacro:property name="camera_height" value="0.025" /> <!-- 摄像头高度(z) -->
<xacro:property name="camera_x" value="0.08" /> <!-- 摄像头安装的x坐标 -->
<xacro:property name="camera_y" value="0.0" /> <!-- 摄像头安装的y坐标 -->
<xacro:property name="camera_z" value="${base_link_length / 2 + camera_height / 2}" /> <!-- 摄像头安装的z坐标:底盘高度 / 2 + 摄像头高度 / 2 --><xacro:property name="camera_m" value="0.01" /> <!-- 摄像头质量 -->
<!-- 摄像头关节以及link -->
<link name="camera">
<visual>
<geometry>
<box size="${camera_length} ${camera_width} ${camera_height}" />
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
<material name="black" />
</visual>
<collision>
<geometry>
<box size="${camera_length} ${camera_width} ${camera_height}" />
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
</collision>
<xacro:Box_inertial_matrix m="${camera_m}" l="${camera_length}" w="${camera_width}" h="${camera_height}" />
</link><joint name="camera2base_link" type="fixed">
<parent link="base_link" />
<child link="camera" />
<origin xyz="${camera_x} ${camera_y} ${camera_z}" />
</joint>
<gazebo reference="camera">
<material>Gazebo/Blue</material>
</gazebo>
</robot>
my_senser_laser.urdf.xacro
<robot name="my_sensors" xmlns:xacro="http://wiki.ros.org/xacro">
<!-- 雷达 -->
<gazebo reference="laser">
<sensor type="ray" name="rplidar">
<pose>0 0 0 0 0 0</pose>
<visualize>true</visualize>
<update_rate>5.5</update_rate>
<ray>
<scan>
<horizontal>
<samples>360</samples>
<resolution>1</resolution>
<min_angle>-3</min_angle>
<max_angle>3</max_angle>
</horizontal>
</scan>
<range>
<min>0.10</min>
<max>30.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<plugin name="gazebo_rplidar" filename="libgazebo_ros_laser.so">
<topicName>/scan</topicName>
<frameName>laser</frameName>
</plugin>
</sensor>
</gazebo></robot>
my_base_camera_laser.urdf.xacro
<!-- 组合小车底盘与摄像头 -->
<robot name="my_car_laser" xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:include filename="my_head.urdf.xacro" />
<xacro:include filename="my_base.urdf.xacro" />
<xacro:include filename="my_camera.urdf.xacro" />
<xacro:include filename="my_laser.urdf.xacro" />
<xacro:include filename="move.urdf.xacro" />
<!-- 雷达仿真的 xacro 文件 -->
<xacro:include filename="my_sensors_laser.urdf.xacro" />
</robot>
第一次加载
car.launch
<launch>
<!-- 将 Urdf 文件的内容加载到参数服务器 -->
<param name="robot_description" command="$(find xacro)/xacro $(find car)/urdf/xacro/my_base_camera_laser.urdf.xacro" />
<!-- 启动 gazebo -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
</include><!-- 在 gazebo 中显示机器人模型 -->
<node pkg="gazebo_ros" type="spawn_model" name="model" args="-urdf -model my_car -param robot_description" />
</launch>
在保存地图时不要将小车模型一起保存,在后续导入的时候还需要重新加载小车。保存到地图模型中会报错。
保存地图为my.world后加载。
car.launch
<launch>
<!-- 将 Urdf 文件的内容加载到参数服务器 -->
<param name="robot_description" command="$(find xacro)/xacro $(find car)/urdf/xacro/my_base_camera_laser.urdf.xacro" />
<!-- 启动 gazebo -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(find car)/world/my.world" />
</include><!-- 在 gazebo 中显示机器人模型 -->
<node pkg="gazebo_ros" type="spawn_model" name="model" args="-urdf -model my_car -param robot_description" />
</launch>
2 导航
新建功能包
roscreate-pkg car_slam gmapping map_server amcl move_base
slam.launch
<launch>
<param name="use_sim_time" value="true"/>
<node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen">
<remap from="scan" to="scan"/>
<param name="base_frame" value="base_footprint"/><!--底盘坐标系-->
<param name="map_frame" value="map"/>
<param name="odom_frame" value="odom"/> <!--里程计坐标系-->
<param name="map_update_interval" value="5.0"/>
<param name="maxUrange" value="16.0"/>
<param name="sigma" value="0.05"/>
<param name="kernelSize" value="1"/>
<param name="lstep" value="0.05"/>
<param name="astep" value="0.05"/>
<param name="iterations" value="5"/>
<param name="lsigma" value="0.075"/>
<param name="ogain" value="3.0"/>
<param name="lskip" value="0"/>
<param name="srr" value="0.1"/>
<param name="srt" value="0.2"/>
<param name="str" value="0.1"/>
<param name="stt" value="0.2"/>
<param name="linearUpdate" value="1.0"/>
<param name="angularUpdate" value="0.5"/>
<param name="temporalUpdate" value="3.0"/>
<param name="resampleThreshold" value="0.5"/>
<param name="particles" value="30"/>
<param name="xmin" value="-50.0"/>
<param name="ymin" value="-50.0"/>
<param name="xmax" value="50.0"/>
<param name="ymax" value="50.0"/>
<param name="delta" value="0.05"/>
<param name="llsamplerange" value="0.01"/>
<param name="llsamplestep" value="0.01"/>
<param name="lasamplerange" value="0.005"/>
<param name="lasamplestep" value="0.005"/>
</node><node pkg="joint_state_publisher" name="joint_state_publisher" type="joint_state_publisher" />
<node pkg="robot_state_publisher" name="robot_state_publisher" type="robot_state_publisher" /><node pkg="rviz" type="rviz" name="rviz" />
<!-- 可以保存 rviz 配置并后期直接使用-->
<!--
<node pkg="rviz" type="rviz" name="rviz" args="-d $(find ar_slam)/rviz/slam_map.rviz"/>
--></launch>
使用键盘控制小车 (noetic版本)
export TURTLEBOT3_MODEL=waffle_pi &&roslaunch turtlebot3_teleop turtlebot3_teleop_key.launch
建图完成后保存
savemap.launch
<launch>
<!-- nav 文件夹可以不创建 -->
<arg name="filename" value="$(find car_slam)/map/nav" />
<node name="map_save" pkg="map_server" type="map_saver" args="-f $(arg filename)" />
</launch>
load_map.launch
<launch>
<!-- 设置地图的配置文件 -->
<arg name="map" default="nav.yaml" />
<!-- 运行地图服务器,并且加载设置的地图-->
<node name="map_server" pkg="map_server" type="map_server" args="$(find car_slam)/map/$(arg map)"/><!--运行rviz-->
<node pkg="rviz" type="rviz" name="rviz" />
</launch>
终端执行,可以add ->MAP /map 看到构建的地图。
catkin_ws $ roslaunch car_slam load_map.launch
全部关闭。
在car_slam ->param 添加以下四个文件
base_local_planner_params.yaml
TrajectoryPlannerROS:
# Robot Configuration Parameters
max_vel_x: 0.5 # X 方向最大速度
min_vel_x: 0.1 # X 方向最小速速max_vel_theta: 1.0 #
min_vel_theta: -1.0
min_in_place_vel_theta: 1.0acc_lim_x: 1.0 # X 加速限制
acc_lim_y: 0.0 # Y 加速限制
acc_lim_theta: 0.6 # 角速度加速限制# Goal Tolerance Parameters,目标公差
xy_goal_tolerance: 0.10
yaw_goal_tolerance: 0.05# Differential-drive robot configuration
# 是否是全向移动机器人
holonomic_robot: false# Forward Simulation Parameters,前进模拟参数
sim_time: 0.8
vx_samples: 18
vtheta_samples: 20
sim_granularity: 0.05
costmap_common_params.yaml
#机器人几何参,如果机器人是圆形,设置 robot_radius,如果是其他形状设置 footprint
robot_radius: 0.12 #圆形
# footprint: [[-0.12, -0.12], [-0.12, 0.12], [0.12, 0.12], [0.12, -0.12]] #其他形状obstacle_range: 3.0 # 用于障碍物探测,比如: 值为 3.0,意味着检测到距离小于 3 米的障碍物时,就会引入代价地图
raytrace_range: 3.5 # 用于清除障碍物,比如:值为 3.5,意味着清除代价地图中 3.5 米以外的障碍物
#膨胀半径,扩展在碰撞区域以外的代价区域,使得机器人规划路径避开障碍物
inflation_radius: 0.2
#代价比例系数,越大则代价值越小
cost_scaling_factor: 3.0#地图类型
map_type: costmap
#导航包所需要的传感器
observation_sources: scan
#对传感器的坐标系和数据进行配置。这个也会用于代价地图添加和清除障碍物。例如,你可以用激光雷达传感器用于在代价地图添加障碍物,再添加kinect用于导航和清除障碍物。
scan: {sensor_frame: laser, data_type: LaserScan, topic: scan, marking: true, clearing: true}
global_costmap_params.yaml
global_costmap:
global_frame: map #地图坐标系
robot_base_frame: base_footprint #机器人坐标系
# 以此实现坐标变换update_frequency: 1.0 #代价地图更新频率
publish_frequency: 1.0 #代价地图的发布频率
transform_tolerance: 0.5 #等待坐标变换发布信息的超时时间static_map: true # 是否使用一个地图或者地图服务器来初始化全局代价地图,如果不使用静态地图,这个参数为false.
local_costmap_params.yaml
local_costmap:
global_frame: odom #里程计坐标系
robot_base_frame: base_footprint #机器人坐标系update_frequency: 10.0 #代价地图更新频率
publish_frequency: 10.0 #代价地图的发布频率
transform_tolerance: 0.5 #等待坐标变换发布信息的超时时间static_map: false #不需要静态地图,可以提升导航效果
rolling_window: true #是否使用动态窗口,默认为false,在静态的全局地图中,地图不会变化
width: 3 # 局部地图宽度 单位是 m
height: 3 # 局部地图高度 单位是 m
resolution: 0.05 # 局部地图分辨率 单位是 m,一般与静态地图分辨率保持一致
在car_slam -> launch 下添加
amcl.launch
<launch>
<node pkg="amcl" type="amcl" name="amcl" output="screen">
<!-- Publish scans from best pose at a max of 10 Hz -->
<param name="odom_model_type" value="diff" /> <!-- 里程计模式为差分 -->
<param name="odom_alpha5" value="0.1" />
<param name="transform_tolerance" value="0.2" />
<param name="gui_publish_rate" value="10.0" />
<param name="laser_max_beams" value="30" />
<param name="min_particles" value="500" />
<param name="max_particles" value="5000" />
<param name="kld_err" value="0.05" />
<param name="kld_z" value="0.99" />
<param name="odom_alpha1" value="0.2" />
<param name="odom_alpha2" value="0.2" />
<!-- translation std dev, m -->
<param name="odom_alpha3" value="0.8" />
<param name="odom_alpha4" value="0.2" />
<param name="laser_z_hit" value="0.5" />
<param name="laser_z_short" value="0.05" />
<param name="laser_z_max" value="0.05" />
<param name="laser_z_rand" value="0.5" />
<param name="laser_sigma_hit" value="0.2" />
<param name="laser_lambda_short" value="0.1" />
<param name="laser_lambda_short" value="0.1" />
<param name="laser_model_type" value="likelihood_field" />
<!-- <param name="laser_model_type" value="beam"/> -->
<param name="laser_likelihood_max_dist" value="2.0" />
<param name="update_min_d" value="0.2" />
<param name="update_min_a" value="0.5" />
<param name="odom_frame_id" value="odom" /> <!-- 里程计odom坐标系 -->
<param name="base_frame_id" value="base_footprint" /> <!-- 添加机器人基坐标系 -->
<param name="global_frame_id" value="map" /> <!-- 添加地图map坐标系 -->
<param name="resample_interval" value="1" />
<param name="transform_tolerance" value="0.1" />
<param name="recovery_alpha_slow" value="0.0" />
<param name="recovery_alpha_fast" value="0.0" />
</node>
</launch>
path.launch
<launch>
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen" clear_params="true">
<rosparam file="$(find car_slam)/param/costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find car_slam)/param/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find car_slam)/param/local_costmap_params.yaml" command="load" />
<rosparam file="$(find car_slam)/param/global_costmap_params.yaml" command="load" />
<rosparam file="$(find car_slam)/param/base_local_planner_params.yaml" command="load" />
</node></launch>
s.launch
<launch>
<!-- 设置地图的配置文件 -->
<arg name="map" default="my_map.yaml" />
<!-- 运行地图服务器,并且加载设置的地图-->
<node name="map_server" pkg="map_server" type="map_server" args="$(find car_slam)/map/$(arg map)"/>
<!--<node pkg="tf" type="static_transform_publisher" name="map_to_odom" args="0.0 0.0 0.0 0 0 0.0 /map /odom 1000"/>-->
<!-- 启动AMCL节点 -->
<include file="$(find car_slam)/launch/amcl.launch" /><!-- 运行move_base节点 -->
<include file="$(find car_slam)/launch/path.launch" />
<!-- 运行rviz -->
<node pkg="rviz" type="rviz" name="rviz" args="-d $(find car_slam)/config/my_map.rviz" /></launch>