用激光雷达建图的前提是cartographer安装成功,能成功运行数据包。
1.首先安装激光雷达驱动,在工作空间src下运行
git clone https://github.com/robopeak/rplidar_ros.git
cd ..
catkin_make_isolated --install --use-ninja
这里编译连接的时候报错无法连接cartographer_ros,解决办法将工作空间下的build_isolated文件夹删除,重新编译
2.在每次启动launch文件时,都要在启动前设置环境变量(在工作环境下)
source ~/catkin_ws/devel_isolated/setup.bsah
source ~/catkin_ws/install_isolated/setip.bash
或者直接将路径写入bashrc文件中
3.修改demo_revo_lds.launch文件
文件路径为/home/zhs/catkin_ws/src/cartographer_ros/cartographer_ros/launch/demo_revo_lds.launch
3.1修改前
<launch>
<param name="/use_sim_time" value="true" />
<node name="cartographer_node" pkg="cartographer_ros"
type="cartographer_node" args="
-configuration_directory $(find cartographer_ros)/configuration_files
-configuration_basename revo_lds.lua"
output="screen">
<remap from="scan" to="horizontal_laser_2d" />
</node>
<node name="cartographer_occupancy_grid_node" pkg="cartographer_ros"
type="cartographer_occupancy_grid_node" args="-resolution 0.05" />
<node name="rviz" pkg="rviz" type="rviz" required="true"
args="-d $(find cartographer_ros)/configuration_files/demo_2d.rviz" />
<node name="playbag" pkg="rosbag" type="play"
args="--clock $(arg bag_filename)" />
</launch>
3.2修改后
<launch>
<param name="/use_sim_time" value="true" />
<node name="cartographer_node" pkg="cartographer_ros"
type="cartographer_node" args="
-configuration_directory $(find cartographer_ros)/configuration_files
-configuration_basename revo_lds.lua"
output="screen">
<remap from="scan" to="scan" />
</node>
<node name="cartographer_occupancy_grid_node" pkg="cartographer_ros"
type="cartographer_occupancy_grid_node" args="-resolution 0.05" />
<node name="rviz" pkg="rviz" type="rviz" required="true"
args="-d $(find cartographer_ros)/configuration_files/demo_2d.rviz" />
</launch>
删除了playbag节点相关内容,之前没删除的时候运行cartographer框架报错。
4. 修改revo_lds.lua文件
文件路径:/home/zhs/catkin_ws/src/cartographer_ros/cartographer_ros/configuration_files/revo_lds.lua
4.1 修改前
options = {
map_builder = MAP_BUILDER,
trajectory_builder = TRAJECTORY_BUILDER,
map_frame = "map",
tracking_frame = "horizontal_laser_link",
published_frame = "horizontal_laser_link",
odom_frame = "odom",
provide_odom_frame = true,
publish_frame_projected_to_2d = false,
use_pose_extrapolator = 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,
rangefinder_sampling_ratio = 1.,
odometry_sampling_ratio = 1.,
fixed_frame_pose_sampling_ratio = 1.,
imu_sampling_ratio = 1.,
landmarks_sampling_ratio = 1.,
}
MAP_BUILDER.use_trajectory_builder_2d = true
TRAJECTORY_BUILDER_2D.submaps.num_range_data = 35
TRAJECTORY_BUILDER_2D.min_range = 0.3
TRAJECTORY_BUILDER_2D.max_range = 8.
TRAJECTORY_BUILDER_2D.missing_data_ray_length = 1.
TRAJECTORY_BUILDER_2D.use_imu_data = false
TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.linear_search_window = 0.1
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.translation_delta_cost_weight = 10.
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.rotation_delta_cost_weight = 1e-1
POSE_GRAPH.optimization_problem.huber_scale = 1e2
POSE_GRAPH.optimize_every_n_nodes = 35
POSE_GRAPH.constraint_builder.min_score = 0.65
return options
4.2 修改后
只修改了如下两句
tracking_frame = "horizontal_laser_link",
published_frame = "horizontal_laser_link",
改为:
tracking_frame = "laser",
published_frame = "laser",
5. 修改后重新编译(工作空间下)
catkin_make_isolated --install --use-ninja
编译的时候遇到问题,显示连接cartographer_ros失败,后删除build_isolated文件夹后重新编译成功。
6. 开始测试
首先启动rplidar的节点launch文件
roslaunch rplidar_ros rplidar.launch
后再运行cartographer框架
roslaunch cartographer_ros demo_revo_lds.launch
打开rivz,启动成功