현재는 데모를 위해 로봇이 돌아다닐 환경을 그려놓았습니다. 이 부분은 사용자가 Gazebo의 Building Editor를 사용해서 쉽게 만들 수 있습니다.

https://s3-us-west-2.amazonaws.com/secure.notion-static.com/f77bcc79-d711-4212-86e8-34927bbe2eab/Untitled.png

이제 이 환경에서 로봇이 돌아다닐 수 있도록 맵을 작성해보겠습니다.

맵을 작성하기 위해 Cartographer를 사용합니다. 기존 gmapping도 존재하지만, gmapping은 하나의 LiDAR만 사용해야 한다는 단점이 존재합니다.

cartographer 소개

cartographer_ros 패키지를 설치합니다.

$ sudo apt install ros-melodic-cartographer-ros
$ sudo apt install ros-melodic-cartographer-rviz

다음으로 cartographer의 설정 데이터, launch 파일을 저장하기 위한 패키지를 생성합니다.

$ catkin create pkg mobile_manipulator_robot_cartographer --catkin-deps cartographer_ros
$ catkin build 
$ source ~/.bashrc

config 디렉토리를 생성하고, map_building.lua 파일을 생성한 후, 다음과 같이 입력해 줍니다.

include "map_builder.lua"
include "trajectory_builder.lua"

options = {
    map_builder = MAP_BUILDER,
    trajectory_builder = TRAJECTORY_BUILDER,
    map_frame = "map",
    tracking_frame = "base_footprint",
    published_frame = "odom",
    odom_frame = "odom",
    provide_odom_frame = false,
    publish_frame_projected_to_2d = false,
    use_odometry = true,
    use_nav_sat = false,
    use_landmarks = false,
    num_laser_scans = 2,
    num_multi_echo_laser_scans = 0,
    num_subdivisions_per_laser_scan = 1,
    num_point_clouds = 0,
    lookup_transform_timeout_sec = 0.6,
    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.min_range = 0.1
TRAJECTORY_BUILDER_2D.max_range = 25.
TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true
TRAJECTORY_BUILDER_2D.use_imu_data = false
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.linear_search_window = 0.15
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.angular_search_window = math.rad(35.)
TRAJECTORY_BUILDER_2D.num_accumulated_range_data = 2

POSE_GRAPH.optimization_problem.huber_scale = 1e2

return options

이제 실행을 위한 launch 파일을 만들어줍니다.

<launch>
<param name="/use_sim_time" value="true" />

<node name="cartographer_node" pkg="cartographer_ros" type="cartographer_node"
        args="  -configuration_directory $(find mobile_manipulator_robot_cartographer)/config
                -configuration_basename map_building.lua"
        output="screen">
        <remap from="odom" to="base_controller/odom"/>
        <remap from="scan_1" to="front_scan"/>
        <remap from="scan_2" to="rear_scan"/>
</node>

<node name="cartographer_occupancy_grid_node" pkg="cartographer_ros"
        type="cartographer_occupancy_grid_node" args="-resolution 0.05" />
</launch>

이제 실행해 줍니다.