이타인클럽

코스 전체목록

닫기

Floorplan Map 만들기

평면도 만들기

토픽 결과물: 2D Floorplan(평면도) Map이 만들어져요!

ROS의 map_server 패키지를 이용하여 3D 모델의 2D 평면도 (floorplan)을 RVIZ에 출력하여, 로봇의 이동 경로 등을 확인할 수 있습니다. map_server에 필요한 파일이 2개 있는데, 먼저 평면도 이미지 파일과 이미지 파일의 설정 파일 (yaml 형식) 입니다.

설명 동영상

Floorplan 이미지

RVIZ에 2D 평면도(floorplan)를 표시하기 위해, 토픽2에서 Gazebo 3D 모델 생성할 때 2D 평면을 캡쳐한 이미지를 사용합니다.

이 이미지의 가로x세로 픽셀수를 재봅니다. 위 이미지의 경우는 314x249 입니다. 주의할 것은 이미지 저장할 때 Floorplan 이외의 여분은 저장하지 않아야 합니다. 여분이 포함되었다면 여분을 제외한 실제 width를 계산하여 사용합니다.

Floorplan 설정 파일

  • map_server가 사용하는 설정 파일 형식은 yaml으로 크게 세가지를 설정해야 합니다. 첫번째가 Floorplan 이미지 파일이고, 두번째가 이미지 resolution이고, 세번째가 Floorplan 중심점입니다.
  • Floorplan 파일을 RVIZ에 출력하기 위해서는 실제 사이즈값을 입력해야 합니다. 이 값은 이미지 resolution으로 이미지 한 픽셀의 실제 거리값입니다. 실제거리 meters/pixels로 얻어집니다. 여기서는 width가 315 pixels이고, 그 실제 거리는 약 5m이므로, resolution은, 즉 pixel당 거리는 5/315=0.015923m 가 됩니다.
  • Floorplan의 중심점 설정은 Gazebo에서 로봇의 적당한 위치를 잡은 후, RVIZ에서 로봇과 Laser 센서값을 출력해 보았을 때, Laser scan과 Floorplan이 맞도록 yaml에 설정해야 합니다. 파일은 패키지의 worlds 디렉터리 밑에 sim_simple.yaml로 저장합니다. 이 방법이 좀 번거롭습니다. 좀 더 간단히 하려면 토픽2에서 3D 환경 생성할 때, 3D 환경의 시작점을 (0,0)으로 하면 됩니다.
image: sim_simple.png  # yaml이 있는 위치 기준 상대경로 입력가능함.
resolution: 0.015923   # 5m/314px
origin: [ -0.4, -0.45, 0.0 ] # map의 중심점 (x, y, theta (rad) )
negate: 0
occupied_thresh: 0.65
free_thresh: 0.19

map_server 설정

아래와 같이 위에서 설정한 floorplan을 rviz에 띄우기 위해서 ROS 패키지인 map_server가 사용되는데, 이것을 위한 launch 파일을 만듭니다. map_server 노드를 실행할 때 필요한 argument가 yaml 형태의 map 설정 파일로 위에서 작성한 sim_simple.yaml입니다. 또다른 argument는 "map"이란 이름을 remap하는 것입니다. 여기서는 "floorplan"이라고 설정하였습니다. map_server를 실행할 때, 파라미터도 하나 설정하는데, map을 출력할 기준 frame을 설정하는 부분입니다. 여기서는 odom frame으로 설정하였습니다. 나중에 로봇이 coverage map을 그릴 때, map frame 으로 변경할 것입니다. 지금은 일단 odom frame으로 설정합니다. 아래와 같이 설정한 후 파일을 rviz.launch로 mobile_robot_sim 패키지밑의 launch 디렉터리에 생성합니다.

<!-- rviz.launch -->
<launch>
  <!-- floorplan -->
  <arg name="floorplan" default="$(find mobile_robot_sim)/worlds/sim_simple.yaml"/>
  <arg name="remap_map" default="floorplan"/>
  <node pkg="map_server" type="map_server" name="map_server" output="screen" args="$(arg floorplan) map:=$(arg remap_map)">  
    <param name="frame_id" value="odom" />
  </node>
  
  <!-- rviz configuration -->  
  <node name="rviz" pkg="rviz" type="rviz" args="-d $(find mobile_robot_sim)/launch/rviz/mobile_robot_sim.rviz"/>
</launch>

위 launch 파일을 보면 rviz 노드도 사용하고 있는 것이 보이는데, 이것은 RVIZ에 출력할 형태를 저장해 놓고 로드하는 부분입니다. 아래 그림과 같이 필요한 topics을 지정하고, 색깔등을 선택하여 저장해 놓습니다. 여기서 RVIZ 설정파일 이름을 mobile_robot_sim.rviz로 하였고 launch 디렉터리 밑의 rviz 디렉터리를 만들고 그 밑에 저장하였습니다.

sim_simple.yaml에서 중심점을 origin: [ -0.4, -0.5, 0.0 ]로 정하였을 때, floorplan이 약간 밑으로 내려온 것처럼 보입니다.

따라서, floorplan을 약간 위로 올립니다. 즉 중심점을 +y 축으로 0.05정도 올린 origin: [ -0.4, -0.45, 0.0 ]을 사용했을 때는 대략 scan과 floorplan과 맞게 됩니다. 여기서 약간 어긋나는 것은 floorplan의 두께등을 반영하지 않았기 때문입니다.

실행

아래와 같이 차례대로 Gazebo launch 파일과 rviz launch 파일을 별도의 terminal에 실행합니다.

# terminal 1
$ roslaunch mobile_robot_sim turtlebot_hokuyo.launch
# terminal 2
$ roslaunch mobile_robot_sim rviz.launch

Gazebo화면과 Floorplan을 RVIZ에 출력한 그림은 아래와 같이 됩니다.

댓글

댓글 본문
graphittie 자세히 보기