home search
Robotics
Autonomous Vehicle
Competition
NAOE
[KABOAT 2022] 인하대학교 i-Tricat221팀 개발 상세 보고서
2022. 08. 25

기본 정보


목차 바로가기


1. Introduction

본 보고서는 제3회 자율운항보트 경진대회(Korea Autonomous Boat Competition 2022, KABOAT 2022)의 참가팀 인하대학교 i-Tricat 221팀(이하 ‘본 팀’ 혹은 ‘팀’)의 임무 수행을 위한 소프트웨어 개발에 대한 상세 사항을 기술하고 있다.

각 임무별 알고리즘 구상 뿐만 아니라 원활한 개발 환경 구성 및 테스트 등을 위한 조치 역시 포함하고 있다.

본 보고서는 개발의 전반적 과정 및 결과에 대한 기술을 주요 목적으로 하며, 2023년 대회를 준비하는 다른 참가팀 혹은 2022년 대회 리뷰를 하고자 하는 팀에게 정보를 제공하는 등의 목적도 있다.

보고서의 구성은 다음과 같다. 우선 Section 2(Development Objectives and Requirements Specification)에서는 경기 규정을 검토하고 다양한 관점에서의 개발 목적 및 요구사항을 나열하여 각 기능 및 조치사항이 도입된 계기를 밝힌다.

이어지는 Section 3(Coordinates and Notations)에서는 본 팀이 사용한 좌표계(Coordinate System)와 주요 notations를 설명한다.

Section 4(Methodologies and Modules)에서는 임무의 수행 및 각종 테스트를 위한 방법론과 모듈을 설명한다. 센서 데이터의 처리부터 제어 방식까지 주요 방법론을 담고 있다.

Section 5(Algorithms and Implementations)에서는 각 임무를 수행하기 위한 알고리즘 구상 및 구현 내용을 기술하고 있다.

Section 6(Useful Tips)은 임무 수행 구현 내용 외에 대회의 준비 및 경기 과정에서 편의성을 증대시킨 각종 조치 사항을 담고 있다.

마지막으로 Section7(Conclusion)에서는 본 팀의 개발 과정 및 내용에 대해 간단히 정리하고 대회 준비 및 진행, 최종 결과를 회고하며 본 보고서를 마무리한다.

사용한 소스코드는 저자의 GitHub Repository에서 확인할 수 있으며, 관련 자료 및 데이터는 저자의 온라인 드라이브 스토리지에서 제공하고 있다.


2. Development Objectives and Requirements Specification

2.1. 경기 규정

대회 주체측에서 제공하는 경기 규정에는 경기 종목과 채점 방식, 채점표 예시가 있다. 규정집은 파일로 확인할 수 있다. 이 절에서는 경기 규정 중 개발 시 유의해야 하는 점을 정리해본다.

경기 종목(임무)은 크게 5가지이며, 개발이 필요한 종목은 그 중 4가지이다.

  • 원격조종 정상 통행: 원격으로 보트를 제어하므로 별도의 기능 개발이 필요하지 않다.
  • 오토파일럿 호핑투어(이하 ‘호핑투어’): 보트가 주어진 지정 위치를 순서대로 추종하여 통과해야 한다.
  • 자율운항 임무 중 장애물 통과(이하 ‘자율운항’): 시작 게이트를 통과하여 최종 게이트를 통과할 때까지 장애물들을 회피하며 이동한다. 예선과 결선으로 나뉘며, 예선은 비교적 폭이 좁은 제2 경기장에서, 결선은 제1 경기장에서 수행한다. 지난 대회와 다른 점은, 일부 수역에서 수면 교란이 있을 수 있다는 점이다.
  • 자율운항 임무 중 도킹(이하 ‘도킹’): 사전에 지정된 표식과 일치하는 도크에 도킹한다. 표식은 보트의 출발 직전 랜덤으로 선택한다. 도크에 충돌하는 것은 따로 벌점을 부과하지 않는다.

모든 종목에서 장애물 혹은 경기장 벽면에 보트가 충돌할 시 벌점(시간 패널티)이 부과된다. 호핑투어는 30초, 자율운항 및 도킹에서는 60초이다. 모든 경기가 임무점수(임무 완료 시간 + 시간 패널티)가 낮은 순으로 순위가 결정되는 기록 경기인만큼, 장애물 및 벽면과 충돌하지 않고 회피하는 것이 무엇보다 중요하다.

호핑투어에서 지정 위치를 통과했음의 기준은 지정 위치의 반경 2m의 원 내부에 보트의 50% 이상이 들어오는 것이다. 따라서 충분히 도착 인정 범위 안쪽을 통과하도록 조치해야 하며, GPS 좌표의 정확성을 보장하거나 이를 보정할 방법이 마련되어야 한다. 또한 임무 수행 중 벽면에 충돌거나 불필요하게 긴 경로를 생성해 임무 시간을 늘리지 않도록 각 지정 위치를 직선에 가까운 경로로 추종하는 것이 필요하다.

자율운항에서는 장애물 회피가 주된 집중사항이 된다. 장애물의 위치가 사전에 공지되지 않고 이를 입력할 수 없으므로, 실시간으로 장애물을 인식하고 이를 회피하는 명령을 생성해야 한다. 보트의 측면 및 후면에 장애물이 충돌하더라도 충돌로 인정하므로 충분한 안전 거리를 확보해야 한다.

도킹에서는 3개의 표식을 인식하고 그 중 타겟 표식을 따로 찾아내야 한다. 표식의 종류는 색상 3개, 모양 3개로 사전 공지되나 각 도크의 표식은 매 경기마다 랜덤하게 결정되고, 타겟 표식 역시 경기 시작 직전 무작위 선택된다. 따라서 색과 모양 모두를 실시간으로 구별할 수 있는 표식 인식 알고리즘이 필요하다.

2.2. 지난 대회의 문제점 분석

본 팀이 속한 인하대학교에서는 지난 1, 2회 대회에 모두 참여하였으며, 본 보고서의 저자는 2회 대회에 i-Tricat211팀으로 참여하였다. 이 절에서 지난 대회에서 발견한 문제점을 분석하고 2022년 대회를 위한 개선사항을 따져본다.

우선, 본 팀이 사용하는 GPS의 정확도가 매우 낮다. RTK 기능을 지원하는 GPS 모델을 사용하고는 있으나 해당 기능이 잘 작동하지 않으며, 경기장 내 수십 팀이 사용하는 GPS 신호의 간섭 등을 받아 심한 경우 수 m의 오차를 보이기도 한다.

특히 작년 대회에서 i-Tricat211팀은 GPS 좌표가 모두 한쪽으로 치우쳐져, 보트가 지정 위치의 원 안으로 충분히 진입하지 못하여 임무 실격 처리를 받은 바 있다. 따라서 GPS의 정확도를 보장하거나 오차를 보정할 수 있는 방법, 혹은 그에 비등하는 대처 방법을 강구해야 한다.

보트의 현 상황을 한 번에 파악할 수 있는 시각화 결과의 부재 역시 문제였다. 본 팀이 보트 내 통신에 사용하는 ROS에서는 주로 10Hz로 모든 연산이 진행되는데, 단순히 텍스트를 출력하는 방식으로는 선수각이나 장애물 인식 결과 등의 센싱 데이터와 알고리즘 수행 시의 각종 연산 결과나 제어값 등을 알기 매우 힘들다. 출력 속도 및 값의 변화가 매우 빠르거니와 수치 정보를 해석하는 데도 어려움이 따른다. 따라서 파악하고자 하는 상황을 시각적으로 표현할 수 있는 시각화 도구가 반드시 필요하다.

대회가 진행되는 공간은 한여름의 야외이므로 자외선이 매우 강하다. 도킹 임무의 경우 표식 인식에 카메라를 필수적으로 사용해야 하는데, 작년 대회에서 사용한 카메라 모델인 Intel Realsense D455 Depth Camera의 경우 강한 자외선 하에서 화면이 보라색으로 변하는 문제점이 있었다. 따라서, 자외선 하에서 정확히 색을 인지할 수 있도록 카메라 모델을 재선정하고 대응 방식을 고안해야 한다.

임무 수행 알고리즘에 사용할 좌표계 역시 중요한 요소이다. 보트의 위치부터 목표지점의 표기, 알고리즘의 수행 등 전반에서 지구 중심을 원점으로 하는 지구고정 좌표계가 아닌, 임의의 좌표계를 설정한다. 그리고 대부분의 경우 일반적이고 직관적으로 사용할 수 있는 데카르트 좌표계를 사용한다.

작년 팀에서 사용한 좌표계는 임의의 한 점을 원점(origin, $O$)으로 하는 ENU 좌표계로, 진북을 $y$축, 동쪽을 $x$축으로 한다. 그러나 보트의 선수각은 $y$축을 기준으로 연산하기 때문에, 이렇게 축을 설정할 경우 각 사분면에서 서로 다른 계산식을 사용해 예외처리를 일일히 진행해야 한다. 예외사항이 많을 때는 그만큼 오류 발생의 가능성과 연산 복잡도, 코드 구현 복잡도도 높아진다.

아래는 2021년 i-Tricat221팀 호핑투어 코드 일부이다. 선수각과 목표각에 따라 에러각을 계산하는 데 수많은 cases 별로 따로 연산을 정의해야 했다.

2021-hopping-code

따라서 최대한 간단하고 예외가 발생하지 않도록 더 나은 방식의 좌표축 설정법을 탐구해야 한다.

본 대회의 준비를 위하여 알고리즘을 검증하는 필드테스트를 수차례 시행한다. 그러나 기상 상황(장마, 폭우, 폭염 등)이나 보트의 재정비 등으로 인하여 직접 물 위에 보트를 띄워 테스트하기 힘든 상황도 많다.

또한 사용되는 각 센서의 수가 많기 때문에 간단한 점검에도 번거로운 연결을 해야 하고, 실제 임무 수행 중의 데이터가 아니기 때문에 실제 상황에서의 알고리즘의 강건성을 검증하기 어렵다. 따라서 테스트 중 수집한 데이터를 이용하여 센서를 직접 연결하거나 실제로 야외 필드테스트를 진행하지 않더라도 알고리즘 및 각종 기능을 검증할 수 있는 방법이 필요하다.

2.3. 개발 목표 및 요구사항

경기 규정 및 지난 대회의 문제점 회고, 보트의 고유한 특징 등으로부터 설정한 개발의 목표 및 요구사항은 아래와 같다.

  • 보트의 특성을 고려하여 경로 탐색 및 제어를 진행해야 한다. 지면의 마찰력을 받는 자동차와는 달리, 보트는 즉각적 제자리 정지가 실질적으로 불가하고 주변 유동으로 인하여 의도한 방향으로 즉시 회전함에 어려움이 있는 등의 특징이 있다.
  • 임무 중 장애물 회피 시 실시간으로 장애물을 탐지하여 그들을 부드럽게 회피해야 하고, 잦은 조향각 변경 등의 불필요한 회전을 최소화해야 한다. 또한 센서가 위치한 보트의 선수 뿐만 아니라 측면 및 선미에도 장애물이 충돌하지 않도록 충분한 여유 공간이 확보되도록 회피 제어 명령을 내려야 한다.
  • 경기가 진행되는 여름철 야외 상황 등 물리적 변수에 대비할 수 있어야 한다. 폭우나 폭염, 강한 자외선 등은 해당 상황은 센서의 정확도에 영향을 줄 수 있으므로 대처방식을 마련해야 한다.
  • 알고리즘 작동 시 불필요한 연산을 줄여 연산 복잡도를 줄이고 메모리를 효율적으로 관리해야 한다. 보트에 설치되는 메인 프로세서는 edge device로 그 성능이 고성능 데스크탑 등에 미치지 못하기 때문이다.
  • 센서에서 입력되는 값(sensory input data)을 처리할 때 지연을 최소화해야 한다. 장애물의 위치는 사전에 주어지지 않으며, 센싱 데이터를 바탕으로 실시간 연산을 해야 한다. 따라서 센서로부터 알고리즘으로 입력되는 센싱값의 지연은 잘못된 연산 결과를 출력할 위험이 있다.
  • 센서의 센싱 데이터의 노이즈 및 에러를 줄이거나 이에 대처할 수 있는 방안이 마련되어야 한다. 또한 해당 데이터를 유용한 형태로 가공하여 사용할 수 있어야 한다.
  • 각종 위험 상황에 강건한 알고리즘을 설계해야 한다. 복잡한 if-else 문의 사용을 줄이고 다양한 상황에 유연하고 단순하게 대처할 수 있어야 한다. 알고리즘의 사전 검증 및 수정을 용이하게 하고 연산 결과의 해석능력(interpretability)를 향상시키기 위함이다.
  • 시각화를 구현하여 보트의 현 위치, 선수각, 목표점, 장애물 등의 파악을 쉽게 해야 한다.
  • 알고리즘 구현 시 모듈화를 진행하여 수정 및 보완, 이식성의 편리함을 증대한다.
  • 직접 모든 센서와 제어기를 연결하고 작동시키지 않아도 알고리즘을 검증할 수 있도록 가상 시뮬레이션이 가능하도록 한다. 또한 특정 기능 테스트를 할 수 있도록 알고리즘을 구현하여 각 모듈의 신뢰도를 검증할 수 있어야 한다.

3. Coordinates and Notations

3.1. 각종 좌표계 및 사용처

본 팀은 미션 수행을 위하여 여러 좌표계를 사용하는데, 이 절에서 관련한 사항을 기술할 것이다.

GPS의 경우 지구 중심을 원점으로 하는 지구고정좌표계(ECEF)로 표현되어(이하 ‘지구고정좌표계’), 본 팀의 보트에 장착된 GPS를 이용하여 DD.MMMMMM 형식의 위도와 경도 좌표를 실시간으로 수신해 사용한다.

본 팀이 사용하는 알고리즘의 주요 좌표계는 ENU 좌표계를 이용한다. 임의의 한 점을 원점(origin, $O$)으로 설정하고 자북 방향(North)을 $X$축, 동쪽(East)을 $Y$축으로 한다. 이를 편의상 ‘항법 좌표계’라 부르며, 센싱 데이터의 표현부터 목표 회전각 계산 및 시각화 등 모든 부분에서 기본적·대표적으로 사용하는 좌표계이다.

enu-coordinates

일반적으로는 $Y$축을 위쪽 방향으로, $X$축을 오른쪽 방향으로 향하도록 설정하나, 본 팀은 위쪽 즉 북쪽 방향을 $X$축으로 삼았다. 그 이유는 2.2절에서 밝힌 바와 같은데, 연산의 복잡성 및 복잡한 case 발생의 가능성을 줄이기 위함이다.

IMU의 지자기 센서로부터 센싱된 데이터를 바탕으로 보트의 선수각을 계산할 때 자북을 기준으로 동쪽으로 회전할수록 (+)값을, 서쪽으로 회전할수록 (-)값을 보이며, 따라서 자북을 0$^\circ$로 하고 [-180, 180]의 선수각 값 범위를 갖는다.

항법 좌표계를 사용할 시 단순한 덧뺄셈으로도 정확하고 일관적인 각도 계산을 할 수 있게 되었으며 시각화까지 편리하게 구현할 수 있게 되었다.

angle-calc-ex

마지막으로, 좌표계의 기준점 및 각 축이 동체(보트)에 따라 움직이는 ‘동체 좌표계’도 사용하여, 선수각 방향을 $x_b$축, 우현 방향을 $y_b$축으로 삼는다.

해당 좌표계는 주로 LiDAR 스캐닝 데이터의 처리에 사용한다. LiDAR는 $x_l$축이 센서의 후방, 즉 보트의 선미 방향이고 $y_l$축이 보트의 우현 방향이며, 데이터는 LiDAR를 원점으로 하는 극좌표계 형식으로 쉽게 변환할 수 있다 - 관련한 사항은 4.2절에서 이어 밝힌다.

최종적으로 서보 모터에 제어 명령을 내릴 때 ‘현재 상태로부터 회전시켜야 할 각’을 계산하므로 LiDAR의 스캐닝 결과로 장애물의 위치를 판단하고 최적의 회전각을 도출할 때 항법 좌표계로의 복잡한 재변환 없이도 단순히 동체 좌표계를 사용해 연산해낼 수 있다.

정확한 ‘동체 좌표계’는 동체의 무게중심에 좌표계의 기준점을 두지만, 본 팀의 경우 단순히 센서의 설치 위치, 즉 보트의 선수를 기준점으로 한다.

아래는 순서대로 동체 좌표계와 LiDAR 좌표계의 예시이다.

boat-coordinates

lidar-coordinates

3.2. 주요 Notations 및 용어 정의

각 절에서 사용하는 주요 표기법(notations)을 아래에 간단히 나타내었다.

  • $(x, y)$: 항법 좌표계로 나타낸 보트의 실시간 위치이다.
  • $\psi$ (heading): 자북에 대한 선수각($^\circ$)이다(이하 ‘선수각’). 자북 방향을 0$^\circ$라 할 때, 선수가 우측으로 회전해 있으면 (0, 180]의 양수을, 좌측으로 회전해 있으면 [-180, 0)의 음수를 출력하며, ‘항법 좌표계’의 표현에 해당한다.

psi-ex

  • $\psi_d$ (desire): 자북을 가리키는 $X$축에 대해 선수각이 위치하길 원하는 각도이다(이하 ‘목표 선수각’ 혹은 ‘목표각’). 호핑투어에서는 원점 $O$에서 다음 지정 위치까지 이은 선분과 $X$축의 사이각을 말한다. 자율운항에서는 장애물 회피 및 최종 게이트 도달을 위하여 회전해야 하는 각도로, 역시 $X$축을 기준으로 나타낸 각도로 ‘항법 좌표계’에 해당한다.
  • $\psi_g$ (goal): 자율운항에서만 쓰이는 기호로, 보트와 최종 게이트를 이은 선분과 현재 선수 방향의 사이각을 말한다. 목표 지점이 선수 방향을 기준으로 우측에 있으면, 즉 보트를 우현 방향으로 돌려야 할 경우에는 (0, 180]의 양수값을, 그 반대의 경우에는 [-180, 0)의 음수값을 가져, ‘동체 좌표계’식 표현이다.
  • $\psi_e$ (error): $\psi = \psi_d$가 되기 위하여 선수를 돌려야 하는 각을 말한다(이하 ‘에러각’ 혹은 ‘차이각’). $\psi_g$와 유사하게 작동한다. 역시 ‘동체 좌표계’식 표현이다.

angle-calc-ex2


4. Methodologies and Modules

4.1. 개발 도구 및 협업 환경

본 팀은 메인 프로세서로서 Intel NUC를, 운영체제로서 Ubuntu 18.04 LTS를 사용하였으며, 전체적 보트 운영을 위해 ROS(Robot Operation System)라는 프레임워크를 사용하였다. 알고리즘 소스코드의 작성에는 수정 후 make 없이도 실행 가능한 Python을 이용하였다.

협업을 위하여 원격 레포지토리인 GitHub를 이용하였고, Notion 및 SNS를 활용해 기타 파일의 공유 및 커뮤니케이션을 진행하였다.

4.2. LiDAR Clustering Module

4.2.1. 모듈의 필요성 및 기본사항

본 팀에서 사용하는 LiDAR는 2D Laser Scanner로, 오직 하나의 channel로 스캐닝 결과를 얻는다. 따라서 물체의 구체적 형상을 구분할 수 없고 각 각도에서의 물체의 존재 여부만 알 수 있다. 따라서 각 물체를 점이 아닌 일종의 블럭 단위로 구분하여 최소한의 semantic 정보를 얻고자 LiDAR의 Point Cloud Data의 클러스터링(Clustering)을 진행하였다.

2D scanning data를 가공하기 위한 여러 오픈소스 라이브러리가 존재하나, 본 팀은 연산 복잡도 개선 및 처리 속도 향상을 위하여 필요한 기능만 최소한으로 개발하였다. 기능 구현은 GitHub에 공개된 오픈소스 라이브러리 tysik의 obstacle_detector를 참고하였다.

4.2.2. 입력 및 출력

이 모듈은 동체 좌표계이자 극좌표계로 표현된 LiDAR의 raw data를 입력으로 받아, 직교 좌표계의 클러스터링된 선분의 집합으로 ‘장애물’ 센싱 데이터의 가공 결과(Obstacle)를 반환한다.

lidar-module-inout

이를 위한 ROS 메시지 타입과 데이터타입(class)를 정의하며, 자세한 사항은 4.2.4절에 기술한다.

4.2.3. 모듈 구조 및 연산 과정

이 모듈은 크게 4가지 구성을 갖는다. 모듈의 각 단계를 수행한 전체 동작 과정을 아래 Figure로 나타내었다.

clustering-process

(A) Group Points 단계는 서로 인접한 점(points)을 각 집합(sets)으로 만든다. 두 점 사이의 거리가 특정 임계값보다 작다면 그 두 점이 같은 집합에 속했다고 판단한다. 반대로 임계값보다 크다면 다른 집합으로 분리한다. 점 간 거리가 작다는 것은 한 물체일 가능성이 높고, 한 물체를 하나의 집합으로 만들어 인식하기 위한 작업이다.

또한 집합으로 묶을 수 있는 점의 최소 개수를 설정하여 한두 개의 점으로 나타나는 노이즈를 효과적으로 제거할 수도 있다. 아래 그림에서 Gruopping시 집합 내 최소 점의 개수 설정의 효과를 볼 수 있다. 입력 데이터에서 보이는 흩뿌려진 점들을 효과적으로 제거하거나 그룹핑한다.

lidar-noise

(B) Split Groups 단계는 (A) Group Points 단계에서 만들어둔 각 집합을 나누는 작업을 수행한다.

묶었던 집합을 다시 나누는 이유는 이러하다. 특정 점이 바로 인접한 점까지의 거리는 가까울 지라도 그가 속해있던 집합 전체에서 보면 다른 점들보다 멀리 떨어져 있을 수 있다. 이 경우 서로 다른 장애물이 하나의 장애물로 분류될 수도 있다.

lidar-grouping

(B) Split Groups의 작업에는 투영(projection)이 사용된다. 한 점이 그 집합에 얼마나 속하는지를 평가하는 기준으로서 집합의 첫 점과 끝 점을 이은 선분으로부터 각 점까지의 거리를 사용한다. 구체적인 구현 방법은 4.2.4절에서 설명한다. 아래 그림은 투영을 사용한 점과 선분 사이의 거리 도출의 예시이다. 특정 점이 해당 집합에 속하는지 구분하는 데 쓰임을 알 수 있다.

lidar-splitting

점에서 수선의 발까지 거리가 임계값보다 작다면 하나의 집합에 속한다고 보아도 좋다는 의미이며, 반대의 경우 집합 내 점의 분포의 일반적 경향성에서 벗어났다고 판단하여 그 지점으로부터 집합을 두 개로 분할한다.

분할된 각 집합에 대해서 다시 (B) Split Groups 단계를 집합 내에서 재귀적으로 수행함으로써 한 집합 내 점들이 최대한 비슷한 선상에 위치한 점만 남도록 한다. 집합의 분할은 집합 내 점의 최소 개수가 되었을 때 중단하기도 한다.

해당 단계는 곡률이 큰 장애물을 표현할 때도 유용하다. Figure처럼 원형 부표의 경우 각 점 간의 거리가 가까워 하나의 집합으로 묶을 수 있지만, 곡선부를 직선으로 표현함으로써 자칫 장애물 일부분을 연산에 포함하지 못하거나 이 결과가 장애물과의 충돌로 이어질 위험이 있다. 따라서 이러한 곡률을 가진 장애물을 표현할 때 (B) Split Groups 단계를 사용하여 작은 여러 개의 집합으로 큰 곡률에도 대응할 수 있다.

(C) Classify Groups 단계는 각 집합이 벽(wall)인지, 일반 부표(buoy)인지 구분한다. 집합의 첫 점과 끝 점의 거리가 사전에 정의한 최소 벽 길이보다 길다면 벽으로 분류한다. 만약 해당 집합이 벽으로 분류되면 (D) Split Walls 단계로 넘어가고, 부표로 분류되면 곧바로 모듈의 최총 출력인 ‘최종 장애물’에 해당 집합을 추가해둔다.

LiDAR는 자율운항 임무에서 장애물의 인식에 사용하는데, 이 임무를 수행함에 있어 벽과 부표를 구분하는 것이 유리하다. 예를 들어, 장애물 회피 시 부표와 벽을 구분하지 않고 똑같은 방식으로 회피하며 장애물까지의 거리를 장애물의 중점으로 사용한다고 가정하자. 길이가 긴 하나의 집합은 의도하지 않은 방향으로 회피각을 선정하게 한다.

아래 그림은 벽/부표 구분 및 분할의 필요성을 보여준다. 긴 벽의 중점까지 거리를 구할 경우 실제보다 긴 거리로 표현될 수 있고, 투영점까지 거리를 구할 경우 장애물의 위치를 덜 고려하게 된다.(A-1, B-1) 벽을 나누어 복수 개의 장애물로 표현하고 중점까지의 거리를 구할 경우, 보다 현실적으로 장애물까지의 거리를 산출할 수 있다. (A-2, B-2)

ob-dist

벽과 부표 모두 회피의 대상이고, 장애물을 부표와 벽의 구분 없이 하나의 ‘장애물(Obstacles)’로 취급한다면, 장애물까지의 거리를 회피에 유리하게 산정하기 위해서는 벽을 적당한 길이로 분할하여 여러 개의 장애물로 표현해야 한다.

(D) Split Walls 단계는 벽으로 분류된, 비교적 긴 집합을 분할하는 작업을 수행한다. 각종 계수 조정을 통해 분할을 할 정도와 벽의 길이 등을 지정할 수 있다. 따라서 해당 모듈을 사용할 알고리즘의 특성에 따라 해당 단계를 사용할 수도, 사용하지 않을 수도 있다.

lidar-splitting-param

4.2.4. 모듈 구현

점 및 점의 집합을 표현하기 위하여 데이터타입(Class)를 정의하였다.

각 점은 Point 자료형으로 나타낸다. Python의 연산자 오버로딩(Operator Overloading)을 사용하여 두 점끼리의 연산 역시 구현하였다. 해당 자료형은 ‘한 점’이 아니라 원점을 시점으로 하는 벡터의 표현 및 연산에도 적용 가능하다.

class Point:
    def __init__(self, x, y):
        self.x = x # 점 혹은 벡터 끝점의 x좌표
        self.y = y # 점 혹은 벡터 끝점의 y좌표

점의 집합은 PointSet 자료형으로 나타낸다.

class PointSet:
    def __init__(self):
        self.point_set = []  # 그룹 내 점의 목록(point_class.py의 Point 클래스)
        self.set_size = 0  # 그룹 내 점의 개수
        self.begin = None  # 그룹의 시작점
        self.end = None  # 그룹의 끝점

4.2.3절에서 밝힌 바와 같이, (B) Split Groups 단계에서 투영의 Python 구현은 PointSet 자료형의 메서드로 구현하며, 그 내용은 아래와 같다.

def projection(self, p):
    """특정 점을 이 PointSet로의 투영점 위치 계산

    PointSet의 첫 점과 끝 점을 선분으로 이은 뒤, 그 위로 점 p의 투영점을 계산함

    Args:
        p (Point): 투영할 포인트 개체
    Returns:
        projection (list): 투영점 좌표
    """
    a = self.end - self.begin  # PointSet의 첫 점과 끝 점 이은 벡터
    b = p - self.begin  # 첫 점과 특정 점을 이은 벡터

    if a.dist_squared_from_origin() != 0:
        projection = self.begin + a * (a.dot(b) / a.dist_squared_from_origin())  # 내적 이용
    else:  # PointSet의 크기가 0 혹은 1인 경우
        projection = self.begin

    return projection

projection

하나의 스캐닝 데이터를 처리하여 출력 결과를 연산하는 모듈의 의사코드는 아래와 같다.

[Sensory Input Processing]
$\phi$를 LiDAR 최소 탐지각으로 초기화함
for 스캐닝 데이터의 모든 점에 대하여
    점의 좌표를 직교좌표계로 변환해 input_points 리스트에 추가
    LiDAR의 각도 증가분만큼 $\phi$를 증가시킴
endfor

[(A) Group Points]
point_set에 input_points의 첫 점을 point_set에 추가해 초기화
for 모든 input_points의 요소에 대하여
    point_set의 끝 점과 해당 점의 거리를 계산함
    if 두 점 사이의 거리 > 임계값 then
        지금까지 모은 점으로 하나의 point_set을 끝내고, 해당 점으로 시작하는 새로운 point_set을 만듦
    else
        point_set에 해당 점을 추가함
    endif
endfor

[(B) Split Groups]
for 모든 point_set에 대해
    최대 거리 max_dist = 0으로 초기화
    for point_set 내 각 점에 대해
        point_set의 양 점끝을 이은 선분으로 점을 투영함
        점과 투영점 사이의 거리를 측정함
        if 거리 > max_dist then
            max_dist = 거리
            해당 점을 분할할 지점으로 설정/업데이트
        endif
    endfor
    if max_dist > 임계값 then
        각 두 그룹을 서로 다른 point_set으로 할당하고 재귀적으로 split_group 단계를 실행
    endif
endfor

[(C) Classify Groups]
for 모든 point_set에 대해
    if point_set의 길이 > 임계값 then
        [(D) Split Walls]
        for point_set 내 모든 점에 대해
            if point_set 첫 점부터 해당 점까지의 거리 > 임계값 then
                해당 위치까지를 새로운 point_set으로 벽을 나눔
                point_set을 obstacles 리스트에 추가
            endif
        endfor
    else
        point_set을 obstacles 리스트에 추가
    endif
endfor

모듈의 출력으로서 장애물(Obstacle)의 집합(ObstacleList)을 내보내는데, 이를 위하여 두 개의 ROS msg를 정의한다.

하나의 장애물을 표현하는 Obstacle.msg 형은 아래와 같이 정의하며 geometry_msgs/Pointxy에 각 점의 위치를 저장한다.

geometry_msgs/Point begin
geometry_msgs/Point end

모든 Obstacle.msg를 저장하는 리스트인 ObstacleList.msg형은 아래와 같다.

std_msgs/Header lidar_header
tricat221/Obstacle[] obstacle

4.3. Control

직접적으로 보트를 이동시키는 데는 두 가지 제어 명령을 내려야 한다. 하나는 선속을 결정하는 thruster(추진기)의 PWM 신호이며, 또 하나는 선수 회전각을 결정하는 서보 모터(thruster와 연결됨)의 회전량 신호이다.

호핑투어에서는 선속을 변화시키며 운항하고, 자율운항 및 도킹에서는 그 값을 고정시켜 일정한 선속으로 운항한다. 따라서 제어 방식은 주로 선수각 회전량에 따른 서보 모터의 제어값 결정에 이용한다.

본 팀은 두 가지 제어법을 사용하였다. 호핑투에는 PID 제어를 사용하였으며, 빠르고 정확한 회피를 요하는 자율운항 및 도킹 미션에는 본 팀이 구현한 별도의 제어값 계산식(이하 ‘Mapping 제어’)을 사용했다.

4.3.1. PID 제어

PID 제어(Proportional-Integration-Differential control)는 피드백 제어(feedback control)의 일종으로, 제어 대상의 출력(output)을 측정해 원하는 값인 설정값(set value)와 비교하여 오차(error)을 계산하고, 제어에 필요한 제어량을 도출된 오차값을 이용해 계산한다. 제어량의 계산은 각각 P, I, D 제어로 구성되어 있으며, 각각 비례항, 적분항, 미분항에 해당한다.

\[x_{ctl} = \mathrm{K}_p \mathrm{e}(t) + \mathrm{K}_i\int_0^t \mathrm{e}(t)\mathrm{d}t + \mathrm{K}_d\frac{de}{dt}\]

호핑투어에서 PID 제어를 사용하는데, 앞서 밝힌 바와 같이 선수 회전량과 선속을 결정한다.

목표하는 회전량을 제어기에 입력하고 출력으로 서보 모터의 제어값을 받는다. 현재 선수각 $\psi$으로부터 목표각 $\psi_d$의 차이, 즉 차이각인 $\psi_e$가 클수록 서보 모터를 더 크게 회전하여 더 빠르게 목표각으로 향하도록 의도한다. 지정 위치를 순차적으로 방문하며 큰 회전을 해야 하는 임무의 특성 상, 빠르게 목표각으로 회전하여 불필요한 경로를 만들지 않는 것이 기록 경기에서 유리하다는 점이 해당 제어기를 사용하는 주된 이유이다. 아래 그림에서 볼 수 있듯이 서보 모터의 회전에 따라 불필요하게 긴 경로가 생성될 수도 있다.

hopping-traj

또한 보트로부터 현재 향하고 있는 지정 위치까지 떨어진 거리를 제어기에 입력하여 추진기의 PWM 신호 제어값을 받는다. 즉 목표점까지 거리가 멀수록 더 빠르게 움직여 수행 시간을 단축시킬 수 있고, 거리가 가까울수록 느리게 움직임으로써 목표점에 안정적으로 진입할 수 있다.

4.3.2. Mapping 제어

자율운항 및 도킹 미션에서 사용하는 제어법은 Angle-Servo Motor의 Mapping 관계를 이용하는 방식이다.

PID 제어는 각 제어기의 게인(gain)($K_p, K_i, K_d$)를 찾는 데 세밀한 조정이 필요하고 적분과 미분 등의 복잡한 수식이 얽혀있어 결괏값에 대한 빠르고 유연한 피드백이 힘들다는 단점이 있다.

따라서 보다 직관적 제어값 산출 및 급작스러운 방향 전환에 대한 대비의 측면에서 ‘서보 모터의 제어 범위’와 ‘선수 회전 가능 범위’의 mapping 관계를 찾는 방식을 도입하였다. 입력값을 $x$로, mapping 결과를 $x_{map}$라 할 때 입력 범위($[\min_{in}, \max_{in}]$)에서 출력 범위($[\min_{out}, \max_{out}]$)로 mapping하는 수식이다.

\[x_{map}=\cfrac{x - \min_{in}}{\max_{in} - \min_{in}} \times (\mathrm{max}_{out} - \mathrm{min}_{out}) + \mathrm{min}_{out}\]

이러한 mapping 결과를 얼마나 민감하게 반응시킬지 결정하기 위하여 추가적인 계수항 $\alpha$을 도입해 최종 제어값 $x_{ctl}$을 도출한다.

\[x_{ctl} = x_{map}*\alpha\]

4.4. Filtering

모든 센서는 기본적으로 정규 분포를 따르는 잡음(노이즈)를 가지고 있다. 매우 빠른 속도로 센싱 데이터를 전달하는 그 특성 상, 대부분의 센서에서 간간히 발생하는 노이즈는 임무를 위한 알고리즘 수행 및 보트 제어에 큰 영향을 미치진 않는다. 그러나 보트의 선수각 연산에 필요한 IMU의 지자기 센서의 경우, 값의 변화가 빈번하고 편차가 매우 큰 편이다. 아래에서 나타낼 모든 알고리즘에서 선수각은 다른 모든 좌표값과 방향각 연산의 기준이 되므로, 그 수치는 최대한 에러 및 노이즈가 없이 안정적이어야 한다. 따라서 항법 좌표계로의 선수각 연산 결과에 필터링을 더하여 노이즈 및 에러를 제거하고 안정적인 값을 얻도록 하였다.

필터링은 비교적 간단한 원리를 가진 ‘이동 평균 필터(moving average filter)’ 방식을 사용하였다. 이동 평균은 노이즈를 없애면서 시스템의 동적인 변화를 고려하기 위해 고안된 방식으로, 최근 측정된 $n$개의 데이터를 평균한다. 새 데이터가 하나 입력되면 가장 오래된 데이터 하나를 버린다. 지금까지 측정된 모든 데이터의 개수를 $k$라고 한다면 $k$번째 이동평균$\bar{x}_k$은 아래와 같은 식으로 구할 수 있다.

\[\begin{aligned} \bar{x}_k &= \cfrac{x_{k - n + 1} + x_{k - n + 2} + \cdots + x_k}{n} \\ &= \bar{x}_{k-1} + \cfrac{x_k - x_{k-n}}{n} \end{aligned}\]

아래 그림은 실제 선수각 데이터(a)와 필터링 후 결과(b)이다. 필터의 크기가 너무 작을 때는 필터링의 효과가 떨어지고(c), 너무 클 때는 지연이 일어난다(d).

maf

필터링은 센서의 입력 뿐만 아니라 서보 모터의 제어값에도 적용하였다. 각 알고리즘의 수행 결과 간혹 이상치가 출력될 수 있다. 만약 이를 그대로 서보 모터를 제어한다면 잘못된 방향으로의 급격한 선수각 회전을 야기할 수 있다. 혹은 비교적 작은 크기로 제어값이 진동하는 경우에도 불필요한 작은 회전을 완화함으로써 부드러운 제어를 가능하게 한다.


5. Algorithms and Implementations

5.1. 오토파일럿 호핑투어

5.1.1. 알고리즘 설계

호핑투어는 주어진 GPS 좌표의 2개 이상의 지정 위치(waypoint)를 순차적으로 방문해야 하는 미션이다. 사전에 각 waypoint를 입력하고, 그 순서대로 현 시점 $t$의 목표 지점(goal)으로 삼는다. 한 목표 지점에 도착하면 다음 순서의 waypoint를 목표 지점으로 교체하여 그를 추종하도록 한다.

호핑투어의 보트 제어에는 PID 제어기를 사용하여 회전각과 전진 속도를 결정한다. 회전각의 측면에서는 다음 지정 위치로 선수 방향을 위치시키기 위하여 $\psi_e$를 제어기에 입력하고 연산을 통해 서보 모터의 출력을 얻는다. 전진 속도의 측면에서는 지정 위치까지 떨어진 거리에 따른 선속을 제어하는 데 PID 제어를 쓰며, 거리가 멀 때는 높은 선속으로 운항하고 가까울 때는 선속을 줄인다.

hopping-flow

아래는 해당 알고리즘의 의사코드이다.

while 모든 waypoints를 다 방문하지 않음
    if 현재 추종하는 waypoint에 도착했음 then
        추종점을 다음 waypoint로 변경함
    else:
        waypoint의 위치와 현재 선수각 간의 에러각($\psi_e$)를 계산함
        PID 제어기에 $\psi_e$를 입력하여 서보 모터 제어값을 출력함
        waypoint로부터 현재 위치 간의 거리를 계산함
        PID 제어기에 거리를 입력하여 추진기 제어값을 출력함
        각각 구한 두 제어값을 이용해 실제로 보트를 이동시킴
    endif
endwhile

5.1.2. 필드테스트 및 경기 수행

호핑투어 알고리즘을 적용하여 직접 필트테스트 및 경기를 수행하였을 때 발견한 현상 및 대처 방안 등을 이 절에서 기술한다.

PID 제어기를 이용한 거리에 따른 선속 제어의 문제점으로, 한 waypoint에 도착한 직후 급출발 문제가 있다. 한 waypoint에 도착하기 직전에는 해당 위치까지 거리가 매우 가까우므로 선속이 최저에 가깝다. 그러나 도착 직후에는 waypoint가 다음의 위치로 바뀌기 때문에 목적지까지의 거리가 매우 멀어지며 선속을 최대에 가깝게 조정하게 된다. 그 결과 최저 속도에서 순식간에 최고 속도를 내게 되며 보트가 급작스런 출발을 하게 되면서 순간적으로 휘청이거나 불필요한 추가 선수 회전을 할 위험이 있다. 급출발은 서보 모터에 부담이 될 뿐만 아니라 불안정한 이동 경로를 생성하여 기록 단축을 어렵게 만들 위험이 있다. 따라서 급출발을 방지하고자 한다면 현재 속도와 목표 속도 차이가 매우 클다면 서서히 속도를 증가시키는 등의 명령을 추가해야 한다.

또 하나의 문제점으로, 현 알고리즘 구현에서는 보트가 한 waypoint에서 다른 waypoint로 이동할 때 커다란 호를 그리며 운항한다는 점이다. 출발 지점으로부터 전면으로 운항할 때는 비교적 직선에 가까운 안정되고 효율적 경로를 보이나, 반대로 돌아오는 방향에서는 호를 그린다. 특히 실제 대회 경기에서는 해당 문제로 말미암아 경기장 벽면에 보트가 충돌하며 전체 지정 위치의 완주에 연속적으로 실패했었다.

작년 대회에서의 문제점으로 GPS의 낮은 정확도가 있었다. 작년 호핑투어에서는 전체적 지정 위치의 좌표가 경기 시작 지점으로 일제히 밀리면서 아직 지정 위치에 도착하지 않은 상태에서도 도착이라 판단하여 통과 인정이 되지 않았었다. 올해의 경우에도 마찬가지로 최대 5~10m 가량의 차이값을 보여 같은 현상이 반복되었다.

따라서 실시간으로 수신하는 GPS 좌표를 ENU 좌표계로 변환한 결과에 임의의 보정을 가해주었다. 우선, 대회 주체측에서 제공한 waypoint가 정확하다는 가정을 한다. 또한 출발 위치(역시 GPS 좌표가 주어져 있다)를 원점인 (0, 0)으로 설정한다. 보트를 원점에 위치시킨 뒤, 알고리즘 시작 시 보트의 좌표값이 (0, 0)과 얼마나 차이가 나는가를 계산하여 이후 모든 수신 좌표값에서 해당 차이값을 보정한다. 예를 들어 출발 위치에서 보트의 좌표가 (3, 4)라면 이를 (0, 0)으로 움직이기 위하여 이후 모든 수신/변환 좌표값의 x에 -3, y에 -4를 더한다.

GPS의 부착 위치도 중요하다. 선수에 부착되어 있다면 선체 전체는 아직 지정 위치의 도착 인정 범위에 들어오지 않았음에도 도착했다고 인식하여 바로 다음 지정 위치로 회전 명령을 내릴 수도 있다. 가장 이상적인 센서의 부착 위치는 선체 longitudianl center이다.

5.2. 자율운항 임무 중 장애물 통과

5.2.1. 알고리즘 구상 배경

목표 지점까지 이동하며 도중에 장애물을 회피하는 경로를 탐색하는 task에는 Dijikstra, A, D 등 유명한 알고리즘이 존재한다. 그러나 대부분의 기존 경로 탐색 알고리즘의 경우 그리드 기반의 방식으로, 이동체의 non-holonomic한 특성을 고려하지 못한다.

최근 자율주행 산업이 발전됨에 따라 실제 이동체에서 사용할 수 있는 다양한 경로 탐색 알고리즘이 개발되며 사용되고 있으나, 지면에서 움직이는 이동체와 유체 속에서 움직이는 선박은 동일한 알고리즘을 사용하는 데 무리가 있다. 또한 비교적 좁은 경기장에 장애물이 근접해 자리하고 있다는 경기 임무의 특성 역시 고려해야 한다.

따라서 본 팀은 다음 시점 $t+1$에 위치하길 원하는 특정 위치($(x_{t+1}, y_{t+1})$)나 몇 개의 timestamp 이후의 예상 경로를 결정하는 것이 아닌, 다음 시점 $t+1$에 가지길 바라는 선수각의 각도인 목표각 $\psi_d$를 탐색하는 방식을 사용했다. 즉, 현 시점 $t$에서의 센싱 데이터를 바탕으로 제어기를 조정하여 $t+1$ 시점의 선수각을 만들고자 한다.

5.2.2. 2021년 i-Tricat211 팀의 자율운항 알고리즘

지난 2021년 대회에서 i-Tricat211 팀은 Fuzzy 방식을 사용하여 목표각을 계산하는 방식을 사용하였다. Rule base로 작동하여 장애물 회피를 하기 위한 Local Path Plan에 해당하는 이 알고리즘은, 장애물의 위치에 따라 선속과 회전각을 선택한다. 만약 보트 전방(탐색 범위) 내에 장애물이 존재하지 않을 경우에는 호핑투어와 마찬가지로 목표 지점을 추종한다.

fuzzy

해당 알고리즘은 실제 경기에서 빠르고 정확한 장애물 회피 운항 결과를 보였으나, 몇 가지 문제점이 존재하였다. 그 중 주요한 문제점은 아래와 같다.

가장 먼저, LiDAR의 스캐닝 결과를 가공하지 않고 개별의 ‘점’으로 사용한다는 점이다. LiDAR 역시 노이즈가 존재할 수 있어 가장 가까이 있는 점이 장애물이 아닌 다른 무언가일 수 있다. 장애물의 형태를 알 수 없으므로 부족하거나 과한 회피각을 산출할 위험도 있다. 좁은 수조에 커다란 장애물이 촘촘히 분포하는 경기장 특성 상 하나의 점만 고려하기에는 복수의 장애물을 연속적으로 회피하며 운항하기에 적합하지 않고 회피 알고리즘의 신뢰성을 보장하기 힘들다.

또한 지역경로탐색과 전역경로탐색이 서로 분리되어 있어 장애물 회피 명령이 최종 목적지 추종과는 반대로 작동할 수 있다. 즉, 최종 목적지는 북쪽에 있는데 바로 전방의 장애물을 회피하기 위하여 남쪽으로 선수각을 회전하려는 상황도 발생할 수 있는 것이다.

수많은 필드테스트를 진행하며 적절한 rule과 파라미터를 일일히 찾아야 하는 것도 많은 부담을 요한다. 실제 경기 장소는 필드테스르를 진행하는 환경과 상이할 수도 있거니와, 수많은 rules를 찾아내는 것은 반복적 실험을 통해서만 안정된 값을 얻을 수 있다.

5.2.3. 알고리즘 설계

본 팀은 위와 같은 문제점을 인지하고 개발 요구사항에 적합한 자율운항 알고리즘을 두 가지 설계했는데, 하나는 ‘점수 기반 목표각 산출’, 또 하나는 ‘선별 기반 목표각 산출’이다. 목표각은 $\psi_d = \psi + \psi_e$이므로 각 알고리즘은 동체 좌표계를 기준으로 받아들인 LiDAR 데이터 및 항법 좌표계를 기준으로 받아들인 선수각 등을 사용하여 $\psi_e$를 계산한다.

⭐️ A. 점수 기반 목표각 산출 알고리즘

점수 기반 목표각 산출 방식은 이동 가능한 각도 모두에 일종의 점수를 부여하여 가장 좋은 점수의 각도를 목표각으로 삼는다. 점수 부여의 기준은 아래 세 가지이며, 각 기준별 계수를 곱해 점수로 할당한다. 최종적으로 $\psi_e$는 각 기준에서의 점수를 모두 합산하여 최소 점수를 가지는 각도로 삼는다.

  • 거리 위험도: 장애물과 거리가 얼마나 가까운가?
    보트로부터 더 가까운 장애물을 우선적으로 회피해야 한다.
  • 각도 위험도: 현재 선수로부터 장애물이 얼마나 가까운가?
    회피 방향을 결정할 때는 선수를 최소한으로 회전하여 불필요한 이동을 최소화하기 위함이다.
  • $\psi_e$목표 위험도: 목표 지점까지 얼마나 선수를 회전해야 하는가?
    회피를 하는 동시에 목표점 역시 추종하도록 한다. 5.2.2절에서 밝힌 Fuzzy 기반 알고리즘의 단점을 개선하기 위함이다.

점수표의 역할을 하는 리스트는 아래와 같은 형태를 띈다.

auto-plan-a

위 표에 따르면 선수를 ~ $^\circ$만큼 회전하는, 즉 $\psi_e = \degree$로 선택한다.

현 시점 $t$에서 $\psi_e$를 결정하는 의사코드는 아래와 같다.

점수를 저장하는 리스트 angle_risk를 모두 0으로 초기화함

for 모든 장애물에 대해
    if 장애물이 탐지 범위 바깥에 위치함 then
        continue
    endif
    장애물의 양쪽에 여유 각도를 더하여 시작/끝 각도를 계산함
    시작/끝 각도의 angle_risk 리스트에서 인덱스를 구함
    보트에서부터 장애물까지의 거리를 구함
    for 장애물의 시작 각도부터 끝 각도까지 모든 각도에 대해
        [각도 위험도]
        angle_risk의 각도 위험도 점수를 더함
        [거리 위험도]
        angle_risk의 거리 위험도 점수를 더함
    endfor
endfor

[목표 위험도]
if 최소 탐지 범위 <= 최종 목표 위치 =< 최대 탐지 범위 then
    for angle_risk의 모든 각도에 대하여
        해당 각도에서 목표점까지 회전해야 할 각도 $\psi_{e, tmp}$를 계산함
        $|\psi_{e, tmp}|$의 범위에 따라 angle_risk의 목표 위험도 점수를 더함
    endfor
else if 최소 탐지 범위 > 최종 목표 위치 then
    0$^\circ$ ~ 최대 탐지 범위의 각도 모두(우현 방향)에 angle_risk의 목표 위험도 점수를 더함
else if 최대 탐지 범위 < 최종 목표 위치 then
    최소 탐지 범위 ~ 0$^\circ$ 모두(좌현 방향)에 angle_risk의 목표 위험도 점수를 더함
endif

[최종 점수 집계]
$\psi_e$를 angle_risk에서 가장 작은 점수를 가지는 각도로 설정함

참고로, 점수표 angle_risk에서 특정 각도를 가지는 인덱스를 구하는 공식과 코드의 구현 형태는 아래와 같다.

\[idx = \cfrac{\phi - \phi_{min}}{\triangle \phi}\]
idx = int((angle - angle_min) / angle_increment)
# 인덱스는 정수이므로 int() 연산을 추가했다.

반대로 점수표 angle_risk에서 특정 인덱스에서의 각도를 구하는 방식은 아래와 같다.

\[\pi = idx \times \triangle \phi + \phi_{min}\]
angle = idx * angle_increment + angle_min

⭐️ B. 선별 기반 목표각 산출 알고리즘
선별 기반 목표각 산출 방식은 다수의 후보 각도(candidates) 중에서 이동 불가능한 각도를 제거한 뒤 최선의 각도들만 선택해나간다. 실제 대회에서 사용한 알고리즘은 선별 기반 목표각 산출 방식이다.

점수 기반 방식은 더 많이 고려해야 할 사항을 계수 조정을 통해서 조절할 수 있다는 장점이 있지만 그만큼 하이퍼 파라미터의 개수가 많아 최적 파라미터값을 찾는데 오랜 시간이 걸린다는 단점이 있다. 선별 기반 알고리즘은 이를 보완하기 위한 조치였으며, 점수 기반 알고리즘의 단순화 버전이라 볼 수도 있다. 두 방식의 차이점은 아래와 같이 정리할 수 있다.

  • 선박으로부터 일정한 거리 이내, 즉 거리 범위 내측의 장애물은 모두 같은 취급을 하였다. 점수 기반 방식에서 ‘거리 위험도’가 없거나 같은 값인 셈이다.
  • 범위 내 장애물이 위치한 각도는 모두 이동이 불가능한 각도로 본다. 이동이 불가능한 각도를 아예 제거함으로써 연산량을 줄였다. 따라서 점수 기반 방식에서 ‘각도 위험도’가 없는 셈이다.
  • 점수 기반 방식의 ‘목표 위험도’처럼 특정 범위마다 가중치를 부여하지 않고, 단순히 목표와 가장 가까운 각 하나만 선택한다.

선별 기반 알고리즘의 작동 방식을 다시 정리하면 이러하다.

  • 장애물이 위치한 각도 및 그 주변 일정 부분을 위험 구역이라 판단하여(a) $\psi_e$의 후보군에서 제외함으로써 이동 가능한 영역만 남겨둔다(b).
  • 이동 가능한 영역 중에서는 최대한 최종 게이트 방향에 가까운 각도를 $\psi_e$로 삼는다. 회피 중에서도 최종 게이트를 추종하도록 하기 위함이다(c).
  • 최종 게이트 방향까지 동일한 각도로 떨어져 있다면, 현재 선수각에서 최대한 덜 회전하는 방향을 $\psi_e$로 삼는다. 불필요하거나 급격한 회전을 줄이기 위함이다(d).

auto-plan-b-ex

auto-plan-b-flow

현 시점 $t$에서 $\psi_e$를 결정하는 의사코드는 아래와 같다.

[장애물 회피]
for 모든 장애물에 대해
    장애물의 양쪽에 여유 각도를 더하여 시작/끝 각도를 계산함
    보트에서부터 장애물까지의 거리를 구함
    if 장애물이 탐지 각도 범위와 탐지 거리 범위 내부에 있음 then
        for 장애물의 시작 각도부터 끝 각도까지 모든 각도에 대하여
            장애물이 존재하는 각도 리스트인 danger_angles 리스트에 추가
        endfor
    endif
endfor
danger_angles에서 중복된 값을 제거함

[최적 에러각 계산]
현 선수각으로부터 목표점까지 회전해야 할 각도 $\phi_g$를 계산함
if 탐지 각도 범위 내 장애물이 없거나, 모두 장애물이 있음 then
    $\psi_e = \phi_g$
else
    for 탐지 각도 범위의 모든 각도에 대하여
        if danger_angles에 해당함 then
            continue
        endif
        $\psi_e = \phi_g$와 가장 가까운 각도, 혹은 0과 가장 가까운 각도로 한다.
    endfor
endif

5.2.4. 필드테스트 및 경기 수행

위 두 알고리즘 중 본 팀이 선택한 것은 선별 기반 목표각 산출 방식이다. 보다 직관적이고 단순하며, 장애물이 존재하는 각도를 애초에 배제하는 방식이기에 확실한 장애물 회피를 할 수 있다는 장점이 있기 때문이다. 해당 알고리즘을 구현하고 실제 테스트를 진행하며 발견한 현상 및 해결 방식을 이 절에서 기술해본다.

해당 구현에서 특이한 점은, 보트의 선속이 빠를수록 회피의 정확도가 높아진다는 점이었다. 여러 원인이 있겠으나, 연산과 제어, 실제 이동의 시간적 차이가 주요한 영향을 끼쳤을 것이라 판단하고 있다. 모든 센서가 위치한 것은 선수이나 제어기인 서보 모터와 thruster가 위치한 것은 선미이다. 따라서 선수에서는 장애물을 회피했다고 판단하였지만 아직 선체 중앙 혹은 선미는 충돌 위험 반경에 위치할 위험이 있는 것이다. 선수에서 목표각을 설정한 뒤 제어 명령을 내린 후, 선미에서 실제 제어를 실행하여 보트의 상태에 변화가 있기까지 시간 간격을 최소한으로 줄이려면 선속을 높이는 방식이 가장 간단하다.

하지만 단순히 선속을 증가시켜 회피 정확도를 향상시키는 방법은 다소 위험 부담이 있다. 보통의 다른 알고리즘의 경우, 선속을 느리게 하면 장애물을 더욱 정확히 인식하고 확실하게 회피할 수 있다. 선속이 높다면 회전 직후 탐지각 바깥에 있다 안쪽으로 들어온 장애물을 인식해 회피하기까지 충분한 시간이 확보되지 않을 위험이 있으므로, 탐지 범위를 과대하게 넓히는 등의 추가 조치가 필요하다. 회피 정확도를 높이기 위하여 권장하는 방식은 선수부터 선미까지 모두 고려하여 여유 공간(충돌 방지 공간)을 설정하거나 탐지 정확도를 향상시키는 등이다.

4.4절에서 밝혔듯, 필터링 기능은 서보모터의 제어값에도 적용할 수 있다. 이는 안정된 운항을 가능하게 한다.

각 센서의 입력 속도 및 알고리즘 연산 속도는 매우 빨라, 본 팀은 약 10Hz이다. 약 0.1초마다 목표각을 새로 산출하므로, 급작스럽게 잘못 연산된 값이 끼어들 수 있으며 이를 그대로 제어 명령에 사용할 경우 서보 모터가 큰 값으로 회전함으로써 보트가 휘청거리며 운항하고 그 과정에서 장애물과 충돌하거나 목표점과 멀어질 수 있다.

특히 선수가 목표지점을 향하고 있는 상태에서 장애물 역시 같은 방향에 위치하고 있을 경우가 위험하다. 매 갱신 시마다 장애물의 양 옆으로 목표각이 빠르게 번갈아 전환된다면, 보트가 한쪽으로 회피하기보다는 휘청거리며 직진하는 형태의 선로를 그리면서 장애물과 충돌하기도 한다.

따라서 회전과 관련한 서보모터 제어에 필터링을 사용함으로써 한 방향으로 조금 더 진행할 수 있도록 시간적 여유를 확보하고 안정적 회피 운항을 가능하게 할 수 있다.

경우에 따라서는 복수 개의 장애물이 탐지 각도 모두를 커버할 상황도 발생한다. 특히 자율운항 예선 경기에서는 좁은 공간에 큰 장애물들이 좁게 분포하고 있으므로 그러한 상황이 빈번하게 발생한다. 알고리즘의 구현 상으로는 해당 경우에는 장애물의 분포와 관계 없이 목표지점을 추종하도록 설정하였다. 탐지 거리 범위 안쪽이긴 하나 비교적 멀리 위치한 장애물이 있다면, 짧은 시간 간격동안은 단순히 목표 지점 추종을 하며 장애물이 적어지길 기다리는 것도 한 방법이기 때문이었다.

그러나 자율운항 예선 경기에서는 연속적 회피를 수행함에 해당 방식이 적합하지 않아 보트가 장애물과 빈번하게 충돌하였다. 이에 대처하기 위하여, 모든 각도에 장애물이 위치할 경우에는 탐지 거리 범위를 더 작게 하여 가까운 장애물들만 고려할 수 있도록 한다. 이로써 이전보다 유연한 회피 명령을 내릴 수 있게 되었다.

LiDAR의 부착 위치도 쉬이 간과할 수 있지만 또한 매우 중요한 요소이기도 하다. LiDAR를 선체의 longitudinal center에 부착하면 전방 뿐만 아니라 측·후방 역시 장애물을 파악할 수 있어 장애물 회피에 매우 유리하다. 그러나 그 높이가 너무 높아 장애물보다 높아지면 2D LiDAR의 특성 상 레이저가 허공에 조사되어 장애물에 반사되지 않아 아예 인식할 수 없어진다. 따라서 선체 설계 시 해당 내용을 숙지하고 흘수와 단자함의 높이 등을 설계해야 한다.

LiDAR가 선수에 있다면 특히 보트의 trim, 즉 길이 방향의 수평을 잘 유지해야 한다. 2D LiDAR가 센서의 수평한 평면으로 360$^\circ$ 방향으로 레이저를 조사하고 반사파를 수신하는 점을 고려한다면, trim by bow를 가질 때(선수 쪽으로 기욺) 보트 전방의 장애물이 아닌 수면으로 레이저가 조사되고 측면으로 갈수록 장애물의 높이보다 높은 곳으로 조사될 수 있다. 이런 경우 제대로 장애물을 탐지할 수 없다. 따라서 trim을 올바르게 맞추어 LiDAR의 스캐닝 레이저가 수평하게 조사될 수 있도록 해야 한다.

5.3. 자율운항 임무 중 도킹

5.3.1. 알고리즘 설계

도킹 임무는 장애물 통과 임무의 최종 구역까지는 4.7절의 자율운항과 동일하게 진행하며, 그 이후부터 지정 표식이 있는 도크에 도킹해야 한다. 해당 임무를 수행하는 알고리즘은 두 개의 기능으로 이루어져 있다. (1) 표식들 중 지정 표식(이하 ‘타겟’)를 인식해야 하며(표식 인식) (2) 목표 표식이 있는 도크 내부로 보트를 진입시켜야 한다(도킹).

⭐️ A. 표식 인식
작년 i-Tricat 211 팀이 사용한 딥러닝 객체 인식 방식의 특징 및 문제점을 알아본다. 작년 팀은 표식 인식에 객체 검출 딥러닝 모델인 YOLOv3 Tiny를 사용하였다. 그러나 딥러닝을 통한 객체 인식을 사용할 경우의 문제점은 아래와 같았다.

  • 실외 경기장의 특성 상 카메라가 자외선 및 조도의 영향을 매우 많이 받기 때문에, 모델의 훈련 데이터를 증강(augment)한다고 해도 그 인식 정확도가 떨어진다.
  • 햇빛이 강하다면 카메라의 노출(exposure)을 낮춘다고 해도 렌즈에 과한 빛이 입력되어 모든 픽셀이 흰색으로 변하는 현상이 일어난다.
  • 비교적 먼 거리에서 도형을 잘 검출하지 못하거나, 검출하더라도 신뢰도가 낮다. 작은 도형을 학습시킬 경우 오검출이 늘어난다.
  • 색과 모양을 모두 하나의 label로 학습시키기 때문에(e.g. red-triangle, blue-circle 등) 둘 중 하나의 특성만 골라 이용하는 데 어려움이 있다.
  • 연산 복잡도가 높으며 대회 임무 중 실시간성이 보장되지 않는다. YOLOv3 Tiny 모델이 one stage detector로 이론상으론 실시간성을 보장하며 R-CNN 등의 two stage detector 보다는 훨씬 연산이 빠름에도 불구하고, GPU를 사용하지 않거나 ONNX 및 TensorRT 등을 적용하는 경량화를 진행하지 않는다면 edge device에서 원하는 속도의 실시간성을 보장할 수 없다. 따라서 센싱 데이터의 입력 및 처리에 상당한 지연 혹은 부하가 발생한다.

따라서 본 팀의 경우, 딥러닝 기반 객체 인식 대신 영상처리를 통한 객체 인식 방식을 택하였다. 영상처리 분야에서 가장 유명한 오픈소스 라이브러리인 OpenCV를 사용하였으며, 영상처리 기반의 객체 인식의 장점은 아래와 같다.

  • 색공간(color space)를 변경하고 각각을 분리할 수 있다. 또한 각 색공간의 선별 범위를 설정함으로써 임무 시의 조도를 고려하여 타겟 표식의 색이 잘 감지되는 범위를 설정할 수 있다.
  • 잡음(노이즈) 제거, 색공간 변화, 밝기 조정 등 이미지의 전처리 과정을 임의대로 조합하고 설정하여 표식 인식이 더 잘 작동하도록 조정할 수 있다.
  • 각 연산 후 어떤 결과 이미지를 얻는지 실시간으로 확인이 가능하다.
  • 특정 색 혹은 모양만 인식할 수 있도록 조정할 수 있다.
  • 딥러닝 기반의 객체인식에 비하여 연산 시간과 부하가 적다.

표식 인식을 위한 단계 및 각 단계의 결과는 그림에 나타내었다.

mark-detect-flow

mark-detect-ex

위 flow chart에서 나타낸 연산의 도입 이유에 대해 몇 가지만 설명하겠다.

2절에서 밝혔듯, 야외 자외선이 매우 강할 경우 카메라에 입사하는 빛이 많아져 영상이 하얗게 변해버리는 현상이 발생한다. 이에 대처하기 위하여 카메라 설정을 조정할 수 있는데, 카메라의 노출(exposure)과 채도(saturation), 대비(contrast) 등을 변경하여 색상이 선명한 영상을 얻게 한다.

cam-config

또한 이미지 데이터에 주로 사용하는 색공간 RGB가 아닌 HSV 색공간을 사용하는데, 이 역시 자외선 하에서 특정 색상을 더욱 잘 추출하기 위함이다. RGB는 각 색상을 기준 색인 빨강, 초록, 파랑의 조합으로 표현하므로 직관성이 떨어지고, 빛 양에 따라 색 자체의 변화가 크기 때문에 야외 상황에서 사용하기 부적합하다. 반면 HSV 색공간은 색조(hue)와 채도(saturation), 명도(value)로 색을 표현하므로 다양한 빛 상황 하에서 색상 자체를 추출하기에 보다 유리하다.

color-trackbar

모폴로지(morphology) 연산은 영상의 객체의 형태와 구조를 분석하고 처리하는 기법이다. 침식(erosion)과 팽창(dilation), 열기(opening)과 닫기(closing) 연산을 사용하여, 객체의 모양을 단순화하거나 잡음을 제거하는 데 주로 사용한다. 본 팀 역시 색 공간 선택으로 노이즈가 포함되거나 도형 내 부분적으로 빈 곳이 생긴 이진화 영상을 처리하는 데 모폴로지 연산을 사용한다. 표식의 영역을 명확하게 함으로써 이어지는 단계인 도형 모양 구분의 정확성을 향상시키도록 돕는다.

도형의 모양을 구별하는 데는 변의 개수를 세는 방식을 사용한다. 삼각형이면 3개, 사각형이면 4개, 십자가이면 12개의 변을 가질 때로 판별하고, 원은 그 이상의 값을 가질 때라 정의했다.

⭐️ B. 도킹
표식을 인식하고 그 중 타겟을 발견하는 기능을 A. 표식 인식에서 구현하였다면, 이 절에서는 전체적 도킹 과정을 설계한다.

360$^\circ$ 회전하며 스캐닝 결과를 도출하는 LiDAR와는 달리, 카메라의 경우 화각(Field of View, FOV)이 비교적 좁다. 본 팀이 사용하는 카메라는 좌우 약 80$^\circ$이다. 도킹 임무에서 표식을 발견하고 그들이 타겟 표식인지 여부를 확인하기 위해서는, 카메라가 표식을 향하고 4.8.1절의 표식 인식 모듈에서 표식을 충분히 인식할 수 있는 거리가 되도록 보트가 직접 이동해야 한다. 이에 본 팀은 아래와 같은 도킹 과정을 고안하였다.

아래 과정의 골자는, 각 도크를 순차적으로 방문하여 표식을 정면으로 보도록 선수각을 조정한 뒤, 해당 도크의 표식이 타겟인지 여부를 판단하는 것이다.

docking-control-flow
docking-control-ex

탐색하고 있는 도크의 표식이 타겟이라면 도크 내부로 진입하는 실제 도킹을 수행해야 한다. 여기서도 두 가지 방식을 고안하였다. 하나는 카메라 프레임의 중앙선을 이용하는 것이고, 또 하나는 도크 방향으로의 추종점을 추종해나가는 것이다.

첫 번째 방법은 카메라 프레임의 수직 중앙선과 표식의 중앙점을 일치시키도록 보트를 제어한다. 카메라는 선체의 선수 방향과 동일 선상에 위치하기 때문에 카메라의 중앙선이 가리키는 방향이 곧 선수 방향이 됨을 이용한 것이다.

docking-control-frame

두 번째 방법은 추종점을 설정하고 이를 추종하는 방식이다. 도크 앞쪽에 설정한 판단 지점에서 시작하여 도크 방향으로 만든 반직선 위에 현재 보트의 위치를 투영한 투영점을 찍는다. 반직선을 따라 투영점의 전방 1~2 m 지점을 추종점으로 삼고, 보트가 해당 점으로 이동하기 위한 선수각 회전 명령을 자율운항 및 호핑투어와 동일하게 하달한다.

보트가 이동하며 연속적으로 해당 연산을 수행하면 매 시점마다 추종점을 전방 1~2m 앞으로 갱신하게 되고, 한 번 목표 도크를 설정한 뒤엔 타겟 인식 결과와는 관계 없이 도크 방향으로 정확히 도킹을 수행할 수 있다는 장점이 있다.

투영점을 설정은 LiDAR clustering module과 동일하게 진행한다. 구제척 진행은 아래 figure을 참고한다.

docking-control-vector

5.3.2. 필드테스트 및 경기 수행

영상처리를 기반으로 객체를 인식했을 때에도 단점은 존재한다.

  • 색공간의 범위를 잘못 지정하면 온전한 도형을 검출하지 못하고, 이는 변의 개수로 도형을 판단할 때 다른 도형이라고 판단할 수 있다 (a).
  • FOV 밖으로 도형이 잘렸을 때 다른 도형으로 오인할 수 있다 (b).
  • 동일한 색의 다른 물체가 이미지 내에 존재하면 이를 표식와 혼동할 수 있다 (c).

docking-exception

따라서 위 단점을 개선하기 위하여 아래와 같은 방법을 추가적으로 구현하였다.

일단 검출 신뢰도를 확보하기 위하여 한 프레임의 연산 결과를 그대로 쓰는 것이 아닌, 일정 횟수만큼 검출 과정을 반복하여 특정 횟수 이상 검출되었을 때 최종 검출이라 판단한다. 예를 들어 400번 중 250번 이상에서 타겟을 검출했을 때만 실제로 검출되었다고 판단하는 것이다. 또한 여러 개의 같은 도형이 검출되었을 때는 가장 큰 넓이를 갖는 도형을 택한다.

아무리 카메라의 설정값을 조정하여 야외의 강한 자외선에 대응한다고 해도, 가장 햇빛이 강한 12시 ~ 2시나 해질녘 등에는 노출값을 0으로 설정해도 영상의 색이 잘 보이지 않는다. 이에 대응하기 위하여 카메라 앞에 ND 편광필터를 부착하면 매우 선명한 영상을 얻는다. 실제로 도킹 경기 당시 해당 필터를 부착하여 해당 상황에 대응하였고 색상을 잘 검출해낼 수 있었다.


6. Useful Tips

6.1. ROS Package 구성 및 모듈화

센서를 구동하는 ROS package는 아래와 같다. 센서 드라이버는 각 센서의 제조사 등에서 제공하는 패키지를 사용했으며, 센서 제원은 대회 제출 보고서를 참고한다.

3rd party libraries는 아래의 것을 사용한다.

  • NumPy 1.16 이상
  • rospy
  • OpenCV 3.4 이상
  • pymap3d 1.8.1

본 팀은 코드의 가독성과 재사용성 향상, 간결화를 위하여 모듈화를 진행하였다. 서로 다른 스크립트에서 모듈을 import 하기 위해서는 아래 코드를 추가하여 파일 경로를 지정해야 한다. 물론 방식은 매우 다양하게 존재하며, 해당 코드는 예시일 뿐이다.

sys.path.append(os.path.dirname(os.path.abspath(os.path.dirname(__file__))))
# src 폴더(해당 스크립트의 상위 폴더)를 경로에 추가함

6.2. roslaunch와 rosbag 활용

ROS에서 roslaunch는 마스터를 구동한 뒤 여러 노드를 각각 실행시키는 것이 아닌, 한 번에 여러 노드를 실행시킬 수 있는 매우 간편한 기능을 가진다. 본 팀의 경우 각 센서와 센싱 데이터를 처리할 노드, 메인 알고리즘을 구동할 노드, 최종 제어를 수행할 아두이노 노드까지를 동시에 수행하도록 roslaunch 파일을 구성해왔다. 올해는 더 나아가 다양한 추가 기능을 사용하여 편의성을 증대했다.

6.2.1. rviz 자동 실행

첫 번째로 Rviz의 설정파일을 불러와 자동 실행했다. Rviz에서는 화면의 구성 등 설정 모두를 저장하고 있는 *.rviz 파일을 저장하고 이를 불러올 수 있는데, roslaunch에서 특정 설정파일을 지정해 Rviz 노드를 실행할 수 있는 것이다.

터미널에서 rviz 노드를 작동시키는 명령어는 아래와 같다.

rviz [-d <rviz 파일 경로>]

roslaunch에서는 이 명령어를 그대로 옮겨오면 된다. 아래는 실제 autonomous.launch 파일 일부이다.

<node pkg="rviz" type="rviz" name="rviz_auto" args="-d $(find tricat221)/rviz/rviz_conf_auto.rviz" />

6.2.2. rosbag 자동 실행

두 번째로, roslaunch로 특정 rosbag 파일을 재생할 수도 있다. 터미널에서 rosbag 파일을 재생하는 명령어는 아래와 같은 형식을 가진다. -l 옵션은 rosbag 파일의 재생이 끝나면 처음부터 자동으로 다시 시작, 즉 무한재생을 가리킨다. -r 옵션은 재생 속도를 결정하는 옵션으로, n로 설정하면 n 배속 재생을 한다. --topics 옵션으로 일부 토픽만 선별해 재생할 수도 있다.

rosbag play <rosbag 파일 경로> [-l] [-r <재생 속도>] [--topics <토픽 이름1> <토픽 이름2> ...]

아래는 220817-181154-hopping-17.bag 라는 이름의 파일 중 /imu/mag, /ublox_gps/fix 토픽을 2배속으로 재생하는 예시이다.

<node pkg="rosbag" type="play" name="rosbag_play" required="true" args="$(find tricat221)/data/rosbag/220817-181154-hopping-17.bag -l -r 2 --topics /imu/mag /ublox_gps/fix"/> 

rosbag 파일을 재생할 뿐만 아니라 녹화까지 할 수도 있다. 아래에 터미널에서 명령어와 roslaunch에서의 예시를 나타냈다. -a 옵션은 현재 발행되고 있는 모든 토픽을 녹화하며, 옵션 없이 토픽을 나열하면 해당 토픽들만 녹화한다. -O 옵션은 파일의 이름(경로)를 지정한다.

# 모든 토픽을 녹화
rosbag record -a [-O <파일 경로>]
# 특정 토픽만 녹화
rosbag record [-O <파일 경로>] <토픽 이름1> <토픽 이름2> ...
<!-- record_example.bag 이라는 이름의 파일을 홈 디렉터리에 생성 -->
<node pkg="rosbag" type="record" name="rosbag_record" required="true" args="record -a -O record_example"  />

6.2.3. rosbag을 통한 시뮬레이션

2.3절에서 밝힌 바와 같이, 알고리즘의 테스트에 일일이 모든 센서를 연결하거나 직접 물에 보트를 띄우기엔 시간적/물리적 제약과 비용이 매우 크다. 따라서 실제 상황에서 기록된 데이터를 사용하여 각 기능 및 알고리즘의 작동 방식을 검증할 수 있어야 한다.

그 방법으로 본 팀은 rosbag을 사용하였다. 야외 테스트 시 rosbag record로 저장한 데이터를 rosbag play로 재생함으로써 실제적 데이터로 현실성 있는 검증을 할 수 있다.

본 팀의 소스코드가 담긴 GitHub repository의 launch 폴더 내 simul_로 시작하는 *.launch 파일들은 실제 센서가 아닌 rosbag play 노드를 작동시켜 센싱 데이터를 얻는다. Figure~는 각 센싱 데이터를 알고리즘에 입력해 작동시키는 rqt graph를 나타낸다.

rqt-graph

6.3. Shell Script 활용

보트를 가동시키고 rosbag으로 녹화를 하기까지는 크게 세 단계를 거쳐야 한다.

  1. 각 센서 및 아두이노에 실행 권한 부여
  2. roslaunch 파일 실행
  3. rosbag record 실행

이들을 한 번에 실행하기 위하여 본 팀은 shell script를 작성했다. src/autonomous.sh 파일을 살펴보자.

#!/bin/sh

# permission to sensors
echo "========== Connect Sensors =========="
sudo chmod 777 /dev/tty* && ls -l /dev/tty*

# rosbag setting
date=$(date "+%y%m%d")
time=$(date "+%H%M%S")
num=$(($(find $(rospack find tricat221)/data/rosbag/${date}-??????-auto-* 2>/dev/null | wc -l)+1))
file_num=$(printf "%02d" "$num")
file_name=${date}-${time}-auto-${file_num}

# launch scripts
echo "\n========== Run =========="
roslaunch tricat221 autonomous.launch do_record:=1 filename:=${file_name}

가장 먼저 센서에 실행 권한을 부여하고 이 목록을 확인한다. 그리고 data/rosbag/ 폴더에 날짜-시간-종목-번호.bag 형식의 bag 파일 이름을 만든다. 그리고 roslaunch 명령어로 launch 파일을 실행할 때, 인자로서 do_recordfilename을 할당한다.

각 launch 파일에는 rosbag record 명령을 내리는 노드를 실행하는데, -O 옵션에 부여할 파일명으로서 앞서 shell script에서 생성한 파일명을 filename 인자에 담아 전달한다. do_record는 해당 노드를 실행할지 말지 결정하는데, 굳이 rosbag record를 실행할 필요가 없다면 해당 값을 False로 설정하면 된다. launch 파일의 해당 부분은 아래와 같다.

<arg name="do_record" default="false" />
<node pkg="rosbag" type="record" name="rosbag_record" required="true" if="$(arg do_record)" args="record -a -O $(find tricat221)/data/rosbag/$(arg filename)"  />

더 자세한 이해는 roslaunch 공식 문서의 문법을 참고하자.

6.4. Rviz 시각화

적절한 시각화 구현의 부재는 작년 대회에서의 문제점이었으며, 이번 대회의 주요 개발 요구사항 중 하나가 바로 시각화였다. 시각화 도구로서 ROS의 3D 시각화 프로그램인 Rviz를 선택했으며, 모듈화를 진행하여 손쉬운 사용과 수정이 가능하도록 했다. 또한 각 상황마다 Rviz 설정 파일 *.rivz를 저장하고 roslaunch 에서 자동 실행함으로써 한 번의 실행만으로 시각화 결과까지 볼 수 있도록 구현하였다.

src/utils/visualizer.py가 Rviz를 사용하는 시각화 모듈(클래스)로, 점(Point)과 화살표(Arrow), 글자(Text), 선(LineList), 그리고 원기둥/원(Cylinder)를 Marker로서 표현할 수 있다. 해당 markers로 선수각이나 목표각, 목적지, 도착 인정 범위, waypoints, 경기장 모양, 보트 이동 경로, 좌표, 장애물, 그리고 위험각도 등을 표시한다.

auto-visual

6.5. Trackbar

OpenCV 라이브러리에서 제공하는 기능 중 하나인 Trackbar(이하 ‘트랙바’)를 이용하면 영상처리가 아니더라도 특정 값을 프로그램 실행 도중에 실시간으로 조정하여 변화 추이를 관찰할 수 있다. 파라미터 파일(/params/*.yaml) 혹은 스크립트(src/*.py)에서 상수를 입력하고 저장한 뒤 다시 실행해 관찰하는 것보다 훨씬 빠르고 편리하다.

특히 LiDAR Clustering 모듈의 각 파라미터 값에 따라 어떻게 결과가 나오는지, 자율운항 알고리즘에서 어떤 파라미터 값이 가장 적절한지 쉬이 파악할 수 있다. 6.4절에서 밝힌 Rviz 시각화와 함께 사용할 시 추이 관찰에 더욱 효과적이다.

lidar-trackbar

또한 도킹 미션에서 HSV 색공간에서 특정 색만 골라낼 색상 범위를 조절하거나, 인식 인정 넓이를 조정할 때도 유용하게 사용할 수 있다.

6.6. Code Formatting

Black은 Python의 code formatting을 돕는 도구로, 코드 한 줄의 최대 길이나 import문의 순서 및 선언 방식, 띄어쓰기 간격, 줄바꿈 간격 등 코드의 포맷을 자동으로 교정한다. 협업 과정에서 각 팀원들의 가독성 및 코드 포맷 일관성을 유지하기 위하여 본 팀은 Black Formatter를 GitHub Actions에서 자동으로 실행함으로써 매 Commit마다 자동 포맷팅을 실시했다. .github/workflows/black_formatter.yaml은 GitHub Actions의 job을 정의하는 파일이며, pyproject.toml은 Black의 세부 설정을 기술하고 있다.

black

유의할 것은, local에서 remote repository로 push하면 포매팅 결과는 오직 remote repository에만 남아 있고, local에서 pull 명령을 내리기 전까진 local의 버전은 한 단계 뒤쳐져 있다. 만약 pull 없이 작업을 계속한다면 commit 충돌이 발생할 수 있다.

이를 방지하기 위하여 pre-commit을 이용할 수도 있다. 해당 프로그램을 이용하면 remote repository에 commit하기 이전에 local 수준에서 포맷팅을 마친 뒤에야 commit을 할 수 있도록 제한을 걸 수 있는데, 본 팀은 이용하지 않았다. 본 팀이 사용한 ROS melodic(18.04) 버전은 Python 2.7과 사용하고 있으나 pre-commit은 Python 3.x대의 버전을 사용해야 하기 때문이다.

Linux 계열 운영체제에서는 alias 명령어를 지원하여 긴 명령어의 단축어(별명)을 지정할 수 있다. 필자는 이를 적극 활용하여 한 단어로도 복잡한 명령을 수행할 수 있도록 하였다. 아래는 본 팀이 활용한 alias 목록이다.

alias cw='cd ~/catkin_ws' # catkin workspace로 이동
alias cs='cd ~/catkin_ws/src/tricat221' # ROS Package 폴더로 이동
alias cm='cd ~/catkin_ws && catkin_make' # catkin make 실행

alias gb='gedit ~/.bashrc' # bash 설정파일 열기
alias sb='source ~/.bashrc' # bash 설정파일 적용
alias pyver='sudo update-alternatives --config python' # Python 버전 변경

alias tty='sudo chmod 777 /dev/tty* && ls -l /dev/tty*' # ttyUSB 계열, ttyACM 계열 센서 권한 부여
alias video='sudo chmod 777 /dev/video* && ls -l /dev/video*' # 카메라 권한 부여
alias ublox='roslaunch ublox_gps ublox_device.launch' # Ublox GPS 실행
alias gps='rostopic echo /ublox_gps/fix' # GPS ROS 토픽 메시지 출력

alias hop='~/catkin_ws/src/tricat221/src/hopping.sh' # 호핑투어 알고리즘 실행
alias auto='~/catkin_ws/src/tricat221/src/autonomous.sh' # 자율운항 알고리즘 실행
alias dock='~/catkin_ws/src/tricat221/src/docking.sh' # 도킹 알고리즘 실행
alias simul_hop='roslaunch tricat221 simul_hopping.launch' # 호핑투어 시뮬레이션 실행
alias simul_auto='roslaunch tricat221 simul_autonomous.launch' # 자율운항 시뮬레이션 실행
alias simul_auto='roslaunch tricat221 simul_docking.launch' # 도킹 시뮬레이션 실행
alias sensor_test='roslaunch tricat221 module_test.launch' # 센서 테스트

또한 Symbolic Link 기능을 활용하여 각 센서의 고유한 이름을 부여하였다. USB로 연결되는 센서들은 매 연결시마다 그 번호가 다르게 부여되는데 이를 고정하기 위한 방법이다. /etc/udev/rules.d/ 경로에 아래와 같은 파일을 추가로 등록하였다. 예를 들자면 GPS는 /dev/ttyUSB0 식이 아니라 /dev/ttyGPS의 별칭 혹은 바로가기를 갖게 된다. 등록 방법은 필자의 블로그 포스팅을 참고한다.

SUBSYSTEM=="tty", ATTRS{idVendor}=="0483", ATTRS{idProduct}=="5740", ATTRS{serial}=="000001010000", SYMLINK+="ttyIMU"
SUBSYSTEM=="tty", ATTRS{idVendor}=="10c4", ATTRS{idProduct}=="ea60", ATTRS{serial}=="34fb725f39f2aa43983443406d85705f", SYMLINK+="ttyLiDAR"
SUBSYSTEM=="tty", ATTRS{idVendor}=="1546", ATTRS{idProduct}=="01a9", SYMLINK+="ttyGPS"
SUBSYSTEM=="tty", ATTRS{idVendor}=="2341", ATTRS{idProduct}=="0044", ATTRS{serial}=="85735313632351A05112", SYMLINK+="ttyARDUINO"

7. Conclusion

7.1. Conclusion

본 보고서는 제3회 자율운항보트 경진대회 KABOAT 2022에 출전한 인하대학교 i-Tricat 221 팀의 소프트웨어 개발 전반의 내용을 상세히 기술하고 있다. 이전 대회에서의 문제점을 파악하고 개발 요구사항을 세우는 기획 단계부터 알고리즘의 설계와 구현, 개발 및 테스트 과정에서의 편리성 증대 방법과 시행착오까지 나타내었다. 본 팀은 대회 경기의 특성에 맞는 알고리즘의 설계와 테스트를 통한 검증에 집중하였으며, 협업 및 개발의 효율성과 편리성을 함양하기 위하여 다양한 기능과 프로그램을 적극 활용하였다.

센싱 데이터의 활용성을 증대하기 위하여 LiDAR Clustering Module 개발하고 IMU 센싱 데이터의 노이즈와 에러를 이동평균필터를 통해 필터링하였으며, 코드 재사용성과 간결화를 위해 각 기능의 모듈화에 집중하였다. 시각화를 통해 현 상황과 알고리즘의 연산 결과를 파악하기 쉽게 하였으며, rosbag 기능을 적극 활용하여 실외 테스트가 불가할 때 알고리즘을 검증하거나 각 모듈의 기능을 테스트하였다.

소스코드는 본 보고서의 저자이자 본 팀의 개발자 역할을 맡은 한은기의 GitHub Repository에서 볼 수 있으며 관련 공개 자료 역시 상단의 드라이브 링크에서 접근할 수 있다.

7.2. Further Study & Developments

약 8개월의 개발 기간 동안 여러 제약 혹은 한계로 인하여 시도해보지 못했거나, 이후 대회에서 추가하면 좋을 사항 등을 이 절에 나타내었다.

GPS 정확도 향상은 필수적이다. 모든 임무에서 이뤄지는 연산은 GPS에서 측정한 보트의 위치를 기반으로 이루어진다해도 과언이 아니다. 보트가 목적지에 도착했는지, 얼마나 멀리 떨어져 있는지 등 기본적이고 필수적 연산을 수행한다. 특히 호핑투어에서는 waypoints의 GPS 좌표와 보트의 현 위치를 기반으로 수행되는 경기인 만큼 그 중요성을 형언할 수 없다. 따라서 RTK를 사용하는 등 오차 범위를 줄이는 노력을 해야 한다.

GPS와 IMU의 융합 역시 고려해볼 사항이다. 두 센서 모두 localization에 사용되는 중요하고 기본적이며 활용도가 매우 높은 센서이나, 현 시점에서는 단순히 현 위치의 좌표점을 파악하거나 선수의 방향을 확인할 뿐이다. 두 센서를 융합한다면 서로가 잘 작동하지 않을 때 이를 보완해주거나, 각 값들의 상호 보정을 가할 수도 있다. 고질적 문제였던 localization의 정확도를 해결하기 위해 한 번쯤 도전해볼 영역이다.

다양한 제어 방식의 도입은 대회 용도 뿐만 아니라 개별적 학습에도 도움이 될 것이다. 지금껏 사용해왔던 PID 제어 외에 다양한 제어법을 익히고 개발하며 어떤 것이 각 종목 혹은 특정 상황에 적합한지 직접 확인할 수 있는 좋은 기회가 될 것이다.

뿐만 아니라 다양한 장애물 회피/경로 생성 알고리즘을 탐색하고 구현하거나 직접 고안해보면서 프로그래밍 능력 향상을 꾀하고, 이와 관련하여 동체의 특성이나 임무 수행 환경 등에 맞는 것을 선택해나가는 과정에서 문제 대처 능력을 키울 수도 있다.

일례로, 작년 필자는 DWA 알고리즘과 A* 알고리즘을 개발하고 적용해보았는데 전자는 복잡하고 불투명한 연산 과정으로 수정이 어렵다는 단점이, 후자는 보트의 non-holonomic 움직임을 반영하지 못한다는 한계점이 있음을 알았었다.

단순한 이상치 제거 혹은 노이즈 감소를 뿐만 아니라 예측의 기능까지 수행하는 칼만필터(Kalman Filter) 역시 사용해보는 것도 좋을 것이다. 물론 학부생 수준에서 칼만필터를 익히고 적용하기에는 매우 어렵고 도전적인 과제가 되겠으나 적재적소에 잘 활용한다면 학습과 대회 준비 모두에 도움이 될 수 있다 생각한다.

올해는 시각화와 시뮬레이터의 효과를 제대로 입증한 해였다. 알고리즘이 현 시점에 파악하고 있는 주변 상태와 중간 연산 결과, 최종 출력하고 있는 결과값 등을 한 눈에 알아볼 수 있으며, 시간에 따른 연속적 변화를 관찰함으로써 작동 여부와 신뢰성 등을 정량적/정성적으로 쉬이 검증할 수 있었다.

다만 아쉬운 것은, 편의상 ‘시뮬레이터’라 명명하였으나 실제로는 녹화한 데이터의 흐름을 다시 재생하는 데 그칠 뿐이라는 데 있었다. 전체적 구동 단계를 ‘센싱 데이터 수집 - 알고리즘 연산 - 제어기 출력 - 보트 이동’으로 나눈다면, 두 번째 단계인 알고리즘 연산 결과만 파악할 수 있는 정도이다. 즉, 제어의 결과까지 알 수는 없기에 ‘목표각은 잘 산출하는 데 배가 왜 이렇게 가지?’라는 테스트 결과를 받을 수도 있다는 뜻이다.

따라서 보다 시뮬레이터 사용 효과를 극대화하려면 선박의 움직임까지 모델링하여 제어 결과까지 구현된 시뮬레이터를 만들어야 한다.

딥러닝 기반의 객체 인식을 한다면 GPU의 활용도 필수적이라 할 수 있다. 작년 i-Tricat 211 팀이 활용한 YOLO v3의 경우 tiny 모델을 사용하더라도 CPU의 연산만으로는 연산 지연 혹은 부하의 급증으로 이어질 수 있다. 대규모 연산은 GPU를 활용하여 처리함으로써 지연이 적고 빠른 연산을 수행해야 딥러닝 기반 방식의 이점을 온전히 취할 수 있다.

각 센서의 또다른 활용성을 탐구해보는 것도 좋다. 카메라나 LiDAR를 융합해 장애물을 인식할 수 있다. 복수 개의 카메라를 이용하는 것도 구상해볼 수 있다. 단순히 복수 개의 카메라에서 받은 영상 각각에 대해 연산을 진행할 수도 있으나, 파노라마 형식으로 stiching을 시켜 보트 전방위의 상황을 파악할 수도 있다. 본 팀은 도킹 미션에서 2개의 카메라를 동시에 사용하는 방안을 구상했으나, 카메라 데이터양이 매우 방대한 특성 상 메모리 부족 현상이 발생해 계획을 철회하였다. 이 문제점을 해결한다면, 복수 개의 카메라 사용은 무궁무진한 가능성을 보여줄 것이다.

LiDAR나 카메라로 SLAM(Simultaneous localization and mapping, 동시적 위치추정 및 지도작성) 혹은 VSLAM(Visual SLAM)에 도전해봐도 좋다. 본 대회는 주로 복수 번의 도전 기회를 주기 때문에 유용하게 사용할 여지가 충분한 기법이다. 매 시점마다 장애물의 위치 정보를 초기화하고 새로 연산을 하기보다는, 그 정보를 map으로 저장하고 안전한 경로를 탐색할 수 있다. 어느 정도의 Global Path Planning이 가능해 보인다.

실제 선박의 제어 방식을 참고하여 제어기를 모델링하는 것도 필요해보인다. 보트의 제어기가 선미에 위치한다면 회전 명령을 내려도 선체의 무게중심을 중심으로 회전하지 않는다. 단순히 회전각을 임의의 수로 더 크게 하는 등 임시적 방편을 사용하기보다는, 실제 선박의 제어방식을 탐구하여 이에 적용하거나, 후륜구동 자동차의 제어방식을 참고하여 제어기를 설계하는 것을 추천한다.

필자가 시도해보려 하였으나 시간적 한계로 포기했던 것은 보트와 드론의 협업 체제 구축이다. 보트의 경우 보트 주변에 위치한 장애물만 파악할 수 있어 인식에 즉각적으로 대응해야 한다. 즉, 먼 미래에 닥칠 상황에 대해서는 전혀 고려하지 못한다. 반면 드론의 경우 상공에서 경기장 전체의 상황을 파악할 수 있기 때문에 보트의 위치 장애물의 위치, 목표점의 위치 등을 모두 파악하여 정보를 제공할 수 있다. 두 이동체의 데이터를 결합하면 보트에서 수집한 데이터만으로는 생성할 수 없었던 전역경로를 생성할 수 있으며, 훨씬 효율적이고 최적의 이동 동선을 계획할 수 있을 것이다.

7.3. Thanks to

필자가 해당 보고서를 상세하게 작성하고 공개하는 가장 큰 이유는, 다음 대회를 준비하는 인하대학교 i-Tricat 부원들 뿐만 아니라 다른 학교의 또다른 학우들에게 도움이 되기 위함이다. 비록 대회 경기 자체만으로는 경쟁 관계에 있다 하더라도, 산업/학계를 함께 이끌어나가는 ‘동료’로서 서로에게 배울 점은 배우고 보완할 점은 보완해나가며 상호 성장을 이루어야 한다. 그것이 이 대회의 목적이며 조선해양공학도로서 추구해야 할 가치라고 생각한다.

필자가 작년 2021년 12월에 개발을 시작하며 가장 먼저 했던 일은, 2021년 자율운항 경진대회의 모든 팀의 제출 보고서 및 발표자료를 정독한 것이었다. 몇 백 페이지에 육박하는 보고서를 학교, 팀과 관계 없이 모두 읽고, 경기를 하며 궁금했던 점이나 주목할만한 각 팀의 특징, 방법론, 적용 기법 등을 기록하였다. 그 중에서 올해 보완했으면 하는 점, 배웠으면 하는 점은 특히 자세히 읽고 추가 조사를 실시하였다.

방향각 연산 부분에서 좌표축 문제에 애를 먹었던 필자는, 부경대학교의 PASS 팀의 보고서를 읽으며 x축과 y축의 위치를 바꾸면 손쉽게 문제가 해결될 수 있음을 알았다. 필드테스트의 체력적/물리적 한계에 힘든 시간을 보냈던 필자는, 한국해양대학교 새울 팀이 rosbag을 활용한 점을 본받아, rosbag 기능과 시각화 기능을 결합하여 최대의 효율을 끌어낼 수 있도록 집중하였다.

위 두 사항은 올해 본 팀이 좋은 성과를 낼 수 있었던 가장 큰 원동력이 되었다. 필자가 도움을 받았던 것처럼, 경험과 지식을 공유하는 선순환이 계속되어 서로의 성장에 도움이 되길 진심으로 바란다.

작년부터 올해까지 필자 개인적으로 가장 큰 성장을 이룬 동력은 자율운항보트 경진대회였다. 이 과정에서 함께해준 인하대학교 i-Tricat 팀의 동료들(💙)과, 지원을 아끼지 않으신 백광준 교수님, 김상현 교수님께 무한한 감사를 드린다. 또한 선의의 경쟁을 펼치며 서로 성장의 발판을 마련한 모든 대회 참가 팀의 학우 분들 역시, 그동안 들여왔던 노력에 비례하는 밝고 희망찬 앞날이 계속되길 진심으로 바란다.

(💙) 가나다순, 괄호는 활동연도
김대웅(20-22), 김명민(22), 김선진(22), 김태민(20-22), 민관돈(20-21), 박정우(22), 박혜리(21), 서무영(20-22), 신채원(21), 양욱진(20-22), 유원준(21-22), 윤호진(22), 이동훈(20-21), 이선우(20-22), 이장근(21), 이주현(22), 이진호(21-22), 이효근(22), 장경준(20-21), 전우빈(22), 조유민(22), 조준희(20-21), 한상석(22)


8. References

  • 황선규, “OpenCV 4로 배우는 컴퓨터 비전과 머신 러닝,” 길벗, 2019, pp. 369-378.
  • 김성필, “칼만 필터는 어렵지 않아,” 한빛아카데미, 2019, pp. 21-29.
arrow_upward arrow_downward
loading