Cartographer离线建图+仿真建图

1 turtule_bot仿真环境采集数据

启动仿真

加载场景

roslaunch turtlebot3_gazebo turtlebot3_house.launch

更改激光雷达参数后的场景:

roslaunch turtlebot3_gazebo turtlebot3_house_hokuyo.launch 

启动可视化仿真

roslaunch turtlebot3_gazebo turtlebot3_gazebo_rviz.launch

启动键盘控制

roslaunch turtlebot3_teleop turtlebot3_teleop_key.launch

rosbag记录数据

记录全部话题

rosbag record -a

记录部分话题

rosbag record /scan /imu /odom

2 cartographer离线建图

目前尚存在问题

3 cartographer在线建图

启动

roslaunch cartographer_ros sim_turtlebot_2d.launch

启动后出现如下警告:

[ WARN] [1587979390.750571170, 567.000000000]: W0427 17:23:10.000000 8793 sensor_bridge.cc:207] Ignored subdivision of a LaserScan message from sensor scan because previous subdivision time 621355973669980000 is not before current subdivision time 621355973669980000

  • 修改lua文件中的配置:
    num_subdivisions_per_laser_scan = 1
    将每个接收到的(多回波)激光扫描分成的点云数。
    细分扫描可以在扫描仪移动时取消扫描获取的扫描。
    有一个相应的轨迹构建器选项可将细分扫描累积到将用于扫描匹配的点云中。
    更改后,以上的报警消失,但是定位效果依然很差!

定位效果差

修改权重参数

TRAJECTORY_BUILDER_2D.ceres_scan_matcher.occupied_space_weight = 1.
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.translation_weight = 25.
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.rotation_weight = 25.

POSE_GRAPH.optimization_problem.local_slam_pose_translation_weight = 1e4
POSE_GRAPH.optimization_problem.local_slam_pose_rotation_weight = 1e4
POSE_GRAPH.optimization_problem.odometry_translation_weight = 1e4
POSE_GRAPH.optimization_problem.odometry_rotation_weight = 1e4

效果依然不好。

修改gazebo turtlebot3上的激光雷达

在操作过程中遇到问题,修改后雷达无法启动,报错。

[gazebo-2] process has died [pid 1813, exit code 255, cmd /opt/ros/kinetic/lib/gazebo_ros/gzserver -e ode /opt/ros/kinetic/share/turtlebot3_gazebo/worlds/empty.world __name:=gazebo __log:=/home/parobot/.ros/log/1c817030-89c9-11ea-be5e-4074e08fa7fa/gazebo-2.log].
log file: /home/parobot/.ros/log/1c817030-89c9-11ea-be5e-4074e08fa7fa/gazebo-2*.log

在终端执行一下操作可以消除错误

killall gzserver

更改激光雷达

参考博文《ROS总结(三)在仿真模型添加激光雷达》

更改launch文件的中的加载项目

/opt/ros/kinetic/share/turtlebot3_gazebo/launch/turtlebot3_house_hokuyo.launch


更改urdf文件中的加载项

/opt/ros/kinetic/share/turtlebot3_description/urdf/turtlebot3_burger.hokuyo.urdf.xacro

 
更改gazebo配置文件中的雷达参数

/opt/ros/kinetic/share/turtlebot3_description/urdf/turtlebot3_burger.hokuyo.gazebo.xacro

  
    Gazebo/Blue
    
      0 0 0 0 0 0
      $(arg laser_visual)
      50
      
        
          
            720
            1
            -2.3550796
            2.3550796
          
        
        
          0.10
          10.0
          0.001
        
        
          gaussian
          0.0
          0.0005
        
      
      
        scan
        base_scan
      
    
  

更改激光雷达参数后,定位效果提升一点,还依然很差。

修改lua文件配置参数

TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true

TRAJECTORY_BUILDER_2D.motion_filter.max_time_seconds = 5.
TRAJECTORY_BUILDER_2D.motion_filter.max_distance_meters = 0.1
TRAJECTORY_BUILDER_2D.motion_filter.max_angle_radians = math.rad(0.3)

TRAJECTORY_BUILDER_2D.ceres_scan_matcher.occupied_space_weight = 1.
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.translation_weight = 25.
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.rotation_weight = 25.

POSE_GRAPH.optimization_problem.local_slam_pose_translation_weight = 1e5
POSE_GRAPH.optimization_problem.local_slam_pose_rotation_weight = 1e5
POSE_GRAPH.optimization_problem.odometry_translation_weight = 1e4
POSE_GRAPH.optimization_problem.odometry_rotation_weight = 1e4

修改参数配置

MAP_BUILDER.use_trajectory_builder_2d = true

TRAJECTORY_BUILDER_2D.num_accumulated_range_data = 10
TRAJECTORY_BUILDER_2D.use_imu_data = false
TRAJECTORY_BUILDER_2D.min_range = 0.1
TRAJECTORY_BUILDER_2D.max_range = 8.0
TRAJECTORY_BUILDER_2D.min_z = -0.05
TRAJECTORY_BUILDER_2D.max_z = 0.5
TRAJECTORY_BUILDER_2D.missing_data_ray_length = 10.0
TRAJECTORY_BUILDER_2D.voxel_filter_size = 0.01
TRAJECTORY_BUILDER_2D.adaptive_voxel_filter.max_length = 0.5
TRAJECTORY_BUILDER_2D.adaptive_voxel_filter.min_num_points = 10
TRAJECTORY_BUILDER_2D.adaptive_voxel_filter.max_range = 50.

TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = false

TRAJECTORY_BUILDER_2D.motion_filter.max_time_seconds = 5.
TRAJECTORY_BUILDER_2D.motion_filter.max_distance_meters = 0.1
TRAJECTORY_BUILDER_2D.motion_filter.max_angle_radians = math.rad(0.3)

TRAJECTORY_BUILDER_2D.ceres_scan_matcher.occupied_space_weight = 1.
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.translation_weight = 25.
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.rotation_weight = 25.


POSE_GRAPH.optimization_problem.local_slam_pose_translation_weight = 1e5
POSE_GRAPH.optimization_problem.local_slam_pose_rotation_weight = 1e5
POSE_GRAPH.optimization_problem.odometry_translation_weight = 1e4
POSE_GRAPH.optimization_problem.odometry_rotation_weight = 1e4

有所提升,但建图整体效果一般。

你可能感兴趣的:(导航)