本人目前大二,写这篇文章是为了怕我忘了,如果有错,大佬们请指出
1.环境
ros1,ubuntu20.04,编译好的catrographyer(注本文所使用雷达为richbeam2D雷达)
2.创建并初始化catkin工作空间(终端窗口1)
mkdir -p ~/catkin_ws/src
cd ~/catkin_ws/
catkin_make
source /opt/ros/noetic/setup.bash
source ~/catkin_ws/devel/setup.bash
3.配置雷达驱动程序(终端窗口2)
将雷达与电脑连接,我看的是雷达的readme,在浏览器里进入http://192.168.8.2,根据ReadMe设置ID
接着将雷达驱动程序(从雷达官网上下载下来的包)放在catkin_ws/src下
在catkin_ws下打开新的终端,输入
catkin_make
source ~/catkin_ws/devel/setup.bash
4.配置Cartographer(终端窗口3)
在catkin_ws/src下面创建文件夹名为your_cartographer_config,进入该文件创建your_cartographer_config.lua和your_cartographer_launch.launch
.launch文件内容
下文中的/scan要改为雷达发布数据的实际的topic名,在雷达的launch文件里面可以找到
<launch>
<!-- 设置不使用模拟时间 -->
<param name="use_sim_time" value="false"/>
<!-- 启动Cartographer节点 -->
<node name="cartographer_node" pkg="cartographer_ros"
type="cartographer_node" args="-configuration_directory $(find your_cartographer_config)/config
-configuration_basename your_cartographer_config.lua"
output="screen">
<!-- 重映射内部使用的雷达数据topic -->
<remap from="echoes" to="/scan"/>
</node>
<!-- 启动Cartographer的占用栅格地图节点 -->
<node name="cartographer_occupancy_grid_node" pkg="cartographer_ros"
type="cartographer_occupancy_grid_node" args="-resolution 0.05" output="screen"/>
</launch>
.lua文件
include "map_builder.lua"
include "trajectory_builder.lua"
options = {
map_builder = MAP_BUILDER,
trajectory_builder = TRAJECTORY_BUILDER,
map_frame = "map",
tracking_frame = "base_link",
published_frame = "odom",
odom_frame = "odom",
provide_odom_frame = true,
use_odometry = false,
use_nav_sat = false,
use_landmarks = false,
num_laser_scans = 1,
num_multi_echo_laser_scans = 0,
num_subdivisions_per_laser_scan = 1,
num_point_clouds = 0,
lookup_transform_timeout_sec = 0.2,
submap_publish_period_sec = 0.3,
pose_publish_period_sec = 5e-3,
trajectory_publish_period_sec = 30e-3,
}
TRAJECTORY_BUILDER_2D.min_range = 0.3
TRAJECTORY_BUILDER_2D.max_range = 30.
TRAJECTORY_BUILDER_2D.missing_data_ray_length = 5.
TRAJECTORY_BUILDER_2D.use_imu_data = false
TRAJECTORY_BUILDER_2D.motion_filter.max_time_seconds = 0.5
TRAJECTORY_BUILDER_2D.motion_filter.max_distance_meters = 0.05
TRAJECTORY_BUILDER_2D.motion_filter.max_angle_radians = math.rad(1.)
MAP_BUILDER.use_trajectory_builder_2d = true
MAP_BUILDER.num_background_threads = 7
return options
接下来回到catkin_ws打开终端输入
export ROS_PACKAGE_PATH=/home/pixie/cartographer/src:$ROS_PACKAGE_PATH
(这里链接的是你编译cartographer的位置,让它能够定位cartographer_ros包)
catkin_make
source ~/catkin_ws/devel/setup.bash
5.启动雷达和cartographer
在第一个终端输入
roscore
在第二个终端输入
roslaunch lakibeam1 lakibeam1_scan_view_usb.launch
因为我是用usb连接的,所以直接使用的这个launch文件
在第三个终端输入
roslaunch /home/pixie/catkin_ws/src/your_cartographer_config/your_cartographer_launch.launch
为了避免找不到我直接使用的路径
现在就可以看到rviz被启动了,接下来的步骤请看这篇的下集