在安装好Cartographer和hokuyo激光雷达之后,我们就可以开始用激光雷达跑了。
本文部分参考博客https://www.cnblogs.com/wenhust/p/6047258.html,但本文安装的是谷歌源码cartographer,lua文件中的变量名字目前是最新的。
一、建立相关文件
1、首先在catkin_google_ws/src/cartographer_ros/cartographer_ros/launch文件夹下建立launch文件demo_hokuyo.launch
<launch>
<param name="/use_sim_time" value="false" />
<node name="cartographer_node" pkg="cartographer_ros"
type="cartographer_node" args="
-configuration_directory $(find cartographer_ros)/configuration_files
-configuration_basename demo_hokuyo.lua"
output="screen">
</node>
<node name="rviz" pkg="rviz" type="rviz" required="true"
args="-d $(find cartographer_ros)/configuration_files/demo_hokuyo.rviz" />
</launch>
2、然后在catkin_google_ws/src/cartographer_ros/cartographer_ros/configuration_files下建立lua配置文件demo_hokuyo.lua
include "map_builder.lua"
include "trajectory_builder.lua"
options = {
map_builder = MAP_BUILDER,
trajectory_builder = TRAJECTORY_BUILDER,
map_frame = "map",
tracking_frame = "laser",
published_frame = "laser",
odom_frame = "odom",
provide_odom_frame = false,
use_odometry = false,
use_nav_sat = false,
use_landmarks = false,
publish_frame_projected_to_2d = false,
num_laser_scans = 1,
num_multi_echo_laser_scans = 0,
lookup_transform_timeout_sec = 0.2,
submap_publish_period_sec = 0.3,
pose_publish_period_sec = 5e-3,
num_subdivisions_per_laser_scan = 1,
num_po