Journal of Korea Robotics Society
[ ARTICLE ]
Journal of Korea Robotics Society - Vol. 15, No. 1, pp.39-47
ISSN: 1975-6291 (Print) 2287-3961 (Online)
Print publication date Feb 2020
Received 2 Dec 2019 Revised 17 Jan 2020 Accepted 28 Jan 2020
DOI: https://doi.org/10.7746/jkros.2020.15.1.039

자율 파지를 위한 수중 로봇 제어 시스템 구축에 관한 연구

이윤건1 ; 이영준2 ; 채준보1 ; 최현택3 ; 여태경
A Study on the Development of Underwater Robot Control System for Autonomous Grasping
Yoongeon Lee1 ; Yeongjun Lee2 ; Junbo Chae1 ; Hyun-Taek Choi3 ; Taekyeong Yeu
1Researcher, Ocean System Engineering Research Division, KRISO, Daejeon, Korea lisser@kriso.re.kr
2Junior Engineer, Ocean System Engineering Research Division, KRISO, Daejeon, Korea leeyeongjun@kriso.re.kr
3Principal Researcher, Ocean System Engineering Research Division, KRISO, Seoul, Korea htchoi@kriso.re.kr

Principal Researcher, Corresponding author: Ocean System Engineering Research Division, KRISO, Daejeon, Korea ( yeutk@kriso.re.kr)

© Korea Robotics Society. All rights reserved.

Abstract

This paper presents a control and operation system for a remotely operated vehicle (ROV). The ROV used in the study was equipped with a manipulator and is being developed for underwater exploration and autonomous underwater working. Precision position and attitude control ability is essential for underwater operation using a manipulator. For propulsion, the ROV is equipped with eight thrusters, the number of those are more than six degrees-of-freedom. Four of them are in charge of surge, sway, and yaw motion, and the other four are responsible for heave, roll, and pitch motion. Therefore, it is more efficient to integrate the management of the thrusters rather than control them individually. In this paper, a thrust allocation method for thruster management is presented, and the design of a feedback controller using sensor data is described. The software for the ROV operation consists of a robot operating system that can efficiently process data between multiple hardware platforms. Through experimental analysis, the validity of the control system performance was verified.

Keywords:

Remotely Operation Vehicle, Thruster Allocation, Robot Operating System, Experiment In Water Tank

1. 서 론

해양 탐사, 해저 구조물 유지 보수, 해저 광물 채취 등에 대 한 중요성이 대두됨에 따라 무인 수중 로봇에 대한 수요가 점 차 증가하고 있다. 무인 로봇을 활용한 수중 작업은 인간이 접 근이 불가능하거나 직접 작업하기 위험한 환경에서 운용하기 적합하다. 다양한 종류의 무인 로봇 중에서 수중 로봇은 대표적 으로 AUV (Autonomous underwater vehicle)와 ROV (Remotely operated underwater vehicle) 두 가지로 분류된다. AUV는 통신 및 전력공급을 위한 테더(Tether)없이 탑재되어 있는 배터리 로 운용되어 이동에 제한이 적어 넓은 지역을 탐사하는데 적 합하다. 광역 항법에 적합한 AUV의 경우 높은 속력으로 이동 하는 능력과 장시간 구동을 위해 낮은 소비전력이 필수기 때 문에 비교적 높은 소비전력을 요하는 추진기의 개수를 줄이고 추진력은 없지만 소비전력이 적은 제어판을 통해 추진방향을 제어하는 경우가 많다[1]. 따라서 낮은 속력에서 자세를 유지하 거나 정밀한 위치 이동을 함에 있어 부적합하다. 반면 ROV는 테더의 길이, 무게 등에 의한 ROV 바디에 가해지는 영향력이 크고 목적지까지의 이동경로가 복잡한 경우 테더 꼬임의 우려 가 있기 때문에 넓은 지역을 탐사하는데 부적합하지만 전력을 소비하는데 비교적 자유로워 낮은 속도에서도 정밀한 제어가 가능하다[2]. 또한 무겁고 전력 소모가 큰 로봇팔을 장착하여 탐사 작업뿐만 아니라 수중 구조물 유지 보수 및 수중 물체 회 수 등 수중 작업이 가능하다는 장점이 있다[3,4].

연구에 사용된 로봇은 로봇팔을 이용한 수중 파지 작업 알 고리즘을 개발하고 검증하기 위해 제작되었다[5]. ROV형태로 제작되었기 때문에 지속적인 전력공급과 안정적인 통신을 할 수 있고 알고리즘 개발을 위한 실험 시 배터리 충전 등 알고리 즘 검증에 불필요한 과정을 없이 지속적인 운용을 할 수 있다. 로봇은 중형 규모의 로봇팔을 수용하며 수조 환경에서 운용 가능한 크기와 무게를 갖는 것이 중요하다. 이를 위해 센서나 장비를 제외한 프레임의 경량화를 통해 무게를 최소화했다. 프레임 경량화로 인해 부족할 수 있는 구조 안정성 보강을 위 해 구조 해석을 통해 보강대를 설치하여 구조 안정성을 확보 했다. 대부분의 수중 로봇들은 로봇팔의 작업 공간 확보를 위 해 로봇의 전방부에 로봇팔을 위치시킨다. 이 경우 전방부와 후방부의 무게 불균형으로 인해 별도의 중량 보상이 필요하 다. 이러한 무게나 크기가 증가하는 문제를 해결하기 위해 개 발 중인 ROV는 로봇팔을 중심부에 위치시키고 상부 프레임 의 앞부분을 개방하여 작업 공간 문제를 해결했다. 일반적인 수중작업용 ROV와 차이점은 로봇팔을 포함한 아래모듈을 분 리하여 탐사만을 목적으로 한 ROV로 운용할 수 있다는 점이 다. 이를 위해 부력체 또한 모듈형으로 제작하여 유사시 부력 체를 추가하거나 제거하여 부력을 조절할 수 있게끔 제작되었 다. 또한 궁극적으로 로봇이 스스로 물체를 식별하고 작업을 수행하기 위해 2대의 수중 카메라와 자체 제작한 수중 레이저 스캐너로 구성된 물체 탐지 및 식별 모듈이 장착되어 있다[6].

대다수의 수중 작업용 로봇들은 2기 이상의 로봇팔을 탑재 하여 한 팔로는 몸체가 움직이지 않도록 지탱을 하고 다른 팔 로 작업을 한다[2,3]. 또는 해저면에 접촉한 상태로 작업을 수행 하기도 한다[7]. 이와 같은 형태로 제작되는 이유는 몸체 접촉 을 통해 로봇의 자세 및 위치를 안정화하여 작업 정밀도를 향 상 시킬 수 있기 때문이다. 하지만 무게와 크기가 커져 별도의 진·회수 장비, 운용 지원용 대형 선박 등 이 필요하기 때문에 운용 시 큰 비용이 발생한다. 본 논문에서 소개하는 로봇은 1 기의 로봇팔로 수중 작업을 수행하기 위해 개발 중이다. 소형 선박으로 진·회수가 가능하도록 플랫폼이 제작되었다.

본 논문에서는 수중에서 무엇과도 접촉이 없는 상태에서 정지하여 수중 작업을 수행하기 위해 로봇의 위치 및 자세 제 어 능력을 발현시키기 위한 연구에 대해 소개한다. 2장에서는 로봇의 운용 및 제어시스템 구축 과정에 대해 설명하고 3장에 서는 파지 작업을 수행하기 위한 운동 제어 성능 검증 실험 결 과에 대해 설명한다. 4장에서는 본 논문의 결론과 앞으로의 연 구 목표에 대해 소개한다.


2. 운용 및 제어 시스템

2.1 플랫폼 구성

선박해양플랜트연구소에서 수중 자율 작업을 위한 핵심 기 술 개발을 위해 운용중인 ROV는 [Fig. 1]과 같다. ROV의 몸체 는 주로 알루미늄과 스테인레스강으로 구성되어 있고 일부 파 트는 경량화를 위해 폴리프로필렌이 사용되었다. ROV를 운 용 중 예상치 못한 문제에 의해 제어 성능을 잃어버렸을 때 수 면으로 떠오르게 하도록 양성 부력을 가지고 있다. 또한 수중 항법 정보 획득 및 상태 모니터링을 위해 다양한 수중 센서 를 장착되었고 수중 자율 작업을 위해 로봇팔과 물체 인식용 장비들이 장착되었다. 추진 시스템은 총 8대의 추진기로 구 성되어 있다. 언급한 장비들과 지상의 제어실과의 통신 인터 페이스를 위해 자체 제작한 2개의 제어용 내압 능력이 있는 Housing이 장착된다. Housing을 통해 ROV의 장비들로 전원 을 분배하고 통신이 이루어진다. ROV는 수중 작업 자세 안정 화를 위해 좌우 대칭형 구조를 가지고 있다. ROV의 사양, 장 착 장비 목록, 장비의 상세 성능에 대한 정보는 [Table 1]에서 확인 할 수 있다.

[Fig. 1]

KRISO Intervention ROV

Specification of ROV

2.2 운용 시스템

본 논문에서 소개하는 ROV의 운용 시스템의 소프트웨어 는 Linux Ubuntu 16.04 버전의 운영체제 하에 ROS (Robot operating system) Kinetic 버전의 로봇용 오픈 소스 메타 운영 체제를 설치하여 구성하였다[8]. ROV를 이용하여 수중 자율 작업을 수행하기 위해서 크게 로봇 운용 파트, 수중 3차원 물 체 인식 파트, 로봇팔 운용 파트로 이루어져있다. 각각의 작업을 수행하기 위해 항법 정보 획득을 위한 센서 데이터, 작업 물체 인식을 위한 센서 데이터, 파지 작업을 위한 로봇팔 센서 데이 터, 추진 시스템 데이터 등 다수의 하드웨어간의 데이터 송수 신이 필수적이다. 본 연구에서는 하드웨어간의 통신이 자유롭 게 이루어지게 하고 다수의 개발자가 동시에 데이터를 송수신 하기 위해 ROS를 Middleware로 선정하였다. ROV를 구성하 는 모든 하드웨어의 동작 및 데이터 송수신을 위해 ROS의 최 소 단위의 실행 프로그램인 Node를 Package화하여 관리하며, Node간의 메시지 발행(Publish) 및 구독(Subscribe)을 통해 정 보 송수신이 이루어지는 ROS 통신시스템을 이용하고 있다. GUI (Graphical user interface)와 조이스틱의 데이터 송수신 시 스템 또한 이를 바탕으로 구성되었다. 발행된 데이터 디스플 레이, 작업자의 명령 전달, 수동 조작을 위한 조이스틱의 명령 은 모두 각각의 Package를 통해 데이터를 주고받는다. 이 모든 과정은 ROS에서 제공하는 메시지 발행과 구독을 통해 이루어 진다. 또한 수중이라는 특수한 환경에서 작업이 진행되기 때 문에 작업자가 ROV의 상태나 작업의 진행 정도를 직접적으 로 파악하기가 매우 어렵다. 수조나 실험을 위해 잘 꾸며진 환 경에서는 수중 카메라를 설치하여 실시간으로 상태 파악을 할 수 있으나 실해역이나 호수 등 실제 작업 환경에서는 카메라 를 통해 실시간 상태 파악이 매우 어렵다. 이러한 환경에서는 작업 중인 ROV의 상태를 수중 카메라를 통해 파악 하더라도 운용 중 발생하는 부유물로 인해 탁도가 높아지므로 직관적으 로 상태 확인 어렵다. 직관적인 ROV의 상태나 작업의 진행 정 도를 파악하기 위해 ROS 제공 가시화 프로그램인 Rviz를 사 용한다. 가시화를 위해 3D 모델링 파일을 기반으로 만들어 로 봇의 모든 하드웨어 요소에 대한 정보를 포함하고 있는 XML 파일 포멧의 URDF, 항법 정보, ROV 및 로봇팔의 상태 정보 등 을 이용하기 때문에 가시화 결과는 실제와 유사한 결과를 보 인다. 또한 실험 중 발행되는 모든 데이터는 ROS 제공 데이터 저장시스템인 ROSbag을 통해 저장되며 이는 항법 성능 평가 시뮬레이션 및 실험 데이터 분석 등에 활용되고 있다.

ROV를 동작하기 위한 User interface는 제어용 컴퓨터에서 실행하는 GUI와 가시화 프로그램 Rviz, ROV 수동 조작을 위한 조이스틱으로 구성되어 있다. GUI를 통해 수동 조작 모드와 자 동 제어 모드 등의 운용 모드를 선택할 수 있다. 자동 제어 모드 경우 GUI를 통해 원하는 작업 수행 명령을 할 수 있다. 수동 조작 모드의 경우 작업자가 조이스틱을 조작하여 입력 값을 조정하 고 입력 값은 각 추진기로 전달된다. 조이스틱을 통한 입력 값은 -1~+1 범위 내에서 조작 가능하며 사전에 설정된 상수 즉, 추진기의 추력 한계를 넘지 않는 값을 곱해 작업자가 원하는 힘과 모멘트를 조이스틱 조작을 통해 발생시킨다. ROV의 운용 시 스템 중 본 논문에서 소개할 자율 주행 모드의 소프트웨어 구성 도는 [Fig. 2]와 같다. 각각의 세부 단계는 다음 절에서 설명된다.

[Fig. 2]

Software architecture of autonomous driving mode

2.3 제어 시스템

2.3.1 좌표계 설정

[Fig. 3]은 본 연구에 사용된 ROV의 좌표계를 나타낸 것이 며 수중 이동체의 일반적인 6자유도 운동은 식 (1)-(3)과 같이 표현할 수 있다[9].

[Fig. 3]

Coordinate system

η=[x,y,z,ϕ,θ,ψ]T(1) 

υ=[u,υ,w,p,q,r]T(2) 

τ=[X,Y,Z,K,M,N]T(3) 

여기서 η는 월드 좌표계에서의 3차원 위치 및 자세 벡터를 나 타내며 x, y, z는 위치 정보를 ϕ, θ, ψ는 자세 정보를 나타낸다. υ는 ROV 바디 고정 좌표계에서의 선속도와 각속도 벡터를 의미하며 u, υ,w는 선속도를 p, q, r각속도를 나타낸다. τ는 ROV의 바디 고정 좌표계에서 작용하는 힘과 모멘트를 나타 내며 X,Y, Z는 바디에 가해지는 힘을K,M,N는 바디에 가 해지는 모멘트를 의미한다. 월드 좌표계에 대해 로봇의 위치 와 자세를 구하기 위해 변환 행렬을 이용한다. 식 (4), (5)를 통 해 바디 고정 좌표계에서의 기체의 속도, 가속도, 각속도 값과 월드 좌표계에서의 로봇의 속도와 각속도 값을 구할 수 있다.

[x˙y˙z˙]=[cθcψsϕsθcψcϕsψcϕsθcψ+sϕsψcθsψsϕsθsψ+cϕcψcϕsθsψsϕcψsθsϕcθcϕcθ][uυw](4) 

[ϕ˙θ˙ψ˙]=[1sϕtθcϕtθ0cϕsϕ0sϕ/cθcϕ/cθ][pqr](5) 

여기서 x˙,y˙,z˙,ϕ˙,θ˙,ψ˙ 은 각각 월드좌표계에서의 로봇의 속도 와 오일러각의 변화량을 의미한다. c는 cos을, s는 sin을, t는 tan를 의미한다. 계산에 사용되는 기체의 가속도와 각속도는 Inertial measurement unit에서 취득하였고, 기체의 이동 속도 는 Doppler velocity log에서 취득하였다. 좌표 변환된 데이터 이용한 확장형 칼만 필터 기반의 항법 알고리즘을 통해 월드 좌표계에서의 항법 정보 η를 계산한다.

ROV를 제어 할 때는 월드 좌표계를 기준으로 제어하기 때문 에 [Fig. 4]와 같이 바디 고정 좌표계 기준의 제어량을 월드 좌표 계 제어량으로 변환해야 한다. 항법 데이터 Feedback 주기와 제 어 주기를 동일하게 하여 식 (6), (7)을 통해 제어 주기 마다 월드 좌표계에서의 surge와 sway를 운동을 위한 제어량을 계산한다.

[Fig. 4]

Coordinate system transformation for rotational movement when moving position

Fsurge{w}=Fsurge{b}cosψ+Fsway{b}sinψ(6) 

Fsway{w}=Fsurge{b}sinψ+Fsway{b}cosψ(7) 

여기서 아래첨자 {b}, {w}는 각각 바디 고정 좌표계와 월드좌 표계를 의미한다.

2.3.2 추력 분배

본 연구에 사용한 ROV의 추진시스템은 4대의 수평추진기 와 4대의 수직추진기로 이루어져있다. ROV가 구현해낼 수 있 는 6자유도의 움직임 보다 많은 수의 추진기로 구성되어 있다. 이와 같은 잉여 구동 시스템(Redundant actuating system)의 효 율적인 6자유도 운동을 구현하기 위해 추진기들의 기구학적 배치를 고려한 추력 분배를 통해 8대의 추진기를 개별 제어하 지 않고 통합하여 제어 한다[10].

추력을 분배하는 과정에서 추진기의 장착 위치와 각도, 무게 중심 등의 정보가 필요하다. 수평과 수직 추진기의 장착 위치 및 각도 , ROV의 무게 중심에 대한 정보는 각각 [Fig. 5(a)], [Fig. 5(b)]에서 확인 할 수 있다. 효율적인 Surge, sway 운동을 위해 수평 추진기를 ROV 바디 프레임 좌표계 y축에 45°가 되 도록 설치했다. 수직 추진기의 경우 추진 시 발생하는 유동과 ROV의 바디와의 간섭을 최소화하여 추력 효율을 증가시키기 위해 ROV 바디 프레임 좌표계 z축에 5°가 되도록 설치하였다. 무게중심 정보는 ROV를 구성하는 모든 센서 및 장비와 구조 물의 실제 무게와 부력을 측정하여 3D 모델링 툴을 이용해 획 득하였다. 위의 정보를 바탕으로 추력을 분배하는 조건은 다 음과 같다. 첫 번째로 수평 추진기는 Surge, sway, yaw 운동만 을 관장하며 수직 추진기는 Heave, roll, pitch 운동만을 관장한 다. 또한 서로의 운동은 독립적이다. 두 번째로 ROV 바디와 추진기는 독립적이며 상호 간섭은 없는 것으로 가정하였다. 벡터τ는 추진기의 추력 벡터 ƒ와 추진기 배치 행렬 TCM을 통해 식 (8)과 같이 표현된다.

[Fig. 5]

Configuration of thrusters: (a) shows the configuration of horizontal thrusters and (b) shows the configuration of vertical thrusters. α1-4 means the angle between the horizontal thruster and the y axis of body fixed coordinates. β5-8 means the angle between the vertical thruster and the z axis of body fixed coordinates. d1-8 means the distance between the axis of propulsion and the center of mass.α1-4 =45°, β5-8 =5°, d1 =0.3443 m, d2 =0.4561 m, d3 =0.4619 m, d4 =0.3490 m, d5,8 =0.5027 m, d6,7 =0.4454 m.

τ=[X,Y,Z,K,M,N]T=[Fx,Fy,Fz,Mx,My,Mz]T=TCMf(8) 

여기서 f=[f1f2f3f4f5f6f7f8]T 를 의미하며 아래 첨자인 1-8은 각각 추진기의 번호를 의미한다. 1-4번 추진기는 수평 추진기, 5-8번은 수직 추진기이다. 추진기 배치 행렬 TCM은 식 (9)와 같다.

TCM=[cosα1cosα2cosα3cosα40000sinα1sinα2sinα3sinα400000000sinβ1sinβ2sinβ3sinβ40000d5d6d7d80000d5d6d7d8d1d2d3d40000](9) 

여기서 각도 α1-4는 바디 고정 좌표계의XY 평면에서 Y축에 대 한 1-4번 추진기의 장착 각도를 나타낸다. β5-8ZX평면에서 Z 축에 대한 5-8번 추진기의 장착 각도를 나타낸다. d1-8은 각각의 평면에서 추진축과 무게 중심 사이의 수직 거리를 나타낸다. 수 평, 수직 추진기에 대해 ROV의 바디 고정 좌표계상에서 각각 XY평면, ZX평면에서 추진기의 추진축의 직선 방정식을 계산 한다. 이를 통해 무게중심과의 거리를 계산한다. TCM+TCM의 의사역행렬을 의미하고 식 (10)을 통해 구할 수 있다.

f=TCMT(TCMTCMT)1τ=TCM+τ(10) 

제시한 방법을 통해 6자유도 운동을 위한 8대 추진기의 입 력 값을 계산할 수 있다. 추력 벡터 ƒ가 실제 추진기의 구동 범 위 내에서 계산될 경우에만 유효하며 추력 한계를 벗어나는 경우는 없다고 가정하여 TCM+을 계산하였다. ƒ가 추진기의 구동 범위를 벗어나 계산될 경우 각 운동의 제어량을 같은 비 율로 감소시켜 추진기를 보호하고 ROV의 운동능력 상실을 방지하는 알고리즘을 추가하였다. TCM+은 식 (11)과 같다.

TCM+=[0.3535570.35350000.51920.35350.35350000.68980.35350.35350000.69860.35350.35350000.5297000.25090.72400.55750000.25090.72290.49320000.25090.71450.49390000.25090.74040.55670](11) 

2.3.3 제어기

제어기 설계에 앞서 입력 대비 출력이 비선형적인 특성을 가지고 있는 추진기의 입출력 관계를 정립하기 위한 사전 연 구가 진행되었다[11]. 6자유도 운동 중 자동 제어가 되는 항목은 Surge, sway, heave, yaw 운동이다. Pitch 제어와 Roll 제어는 제 외한다. ROV는 좌우 대칭의 구조로 Roll 각은 거의 발생하지 않으나 로봇팔의 무게는 기중 무게 약 51 kg으로 전체 로봇의 20% 이상의 높은 무게 비율을 차지하고 작업 방향이 주로 로봇 의 전방이기 때문에 Pitch 각이 발생한다. 이 문제를 해결하기 위해 무게추를 이용해 전후 균형을 맞추어 Pitch 각을 제거한다.

Surge, sway, yaw 운동을 제어하기 위한 제어기로는 대표적인 Feedback 제어방식인 PID 제어기(Proportional integral differential controller)를 선정하였다. 제어 이득(Gain)을 얻기 위해, 먼저 스텝 응답법(Step response method)을 이용하여 surge, sway, yaw 운동에 대한 시스템 예측(System identification)을 수행하였고, 다음으로 예측된 시스템을 활용하여 PID 이득 조정(PID gain tuning)을 진행하였다. 여기서, 시스템 예측과 PID 이득 조정 은 MATLAB에서 지원하는 툴을 사용하였다. [Fig. 6]은 Yaw 방 향에 대하여 PID 이득을 얻기 위해 수행한 시스템 예측 시험 결과를 보여준다. 여기서 상부 그래프는 스텝응답실험을 통해 얻어진 Yaw 각도 정보, 하부는 스텝응답결과를 이용하여 예 측된 모델의 출력값이다. 예측된 모델은 2차 전달함수(Second order transfer function)이며, 실제 계측된 모델과는 약 26%정 도의 오차를 가진다.

[Fig. 6]

System identification in Yaw : (top) Experimental result of step response, (down) Output of identified model

양성 부력을 가지고 있는 ROV의 심도 제어를 위해서는 PD 제어기에 부력 보상(Feedforward) 방식 제어기를 추가하여 양 성 부력에 의해 정상 상태 오차가 발생하는 문제를 해결했다. 정상 상태 오차 문제의 경우 적분 제어기를 이용하여 해결 할 수 있지만 응답 속도 문제와 제어 목표치가 변경되었을 때 시스 템이 불안해지는 문제가 발생할 수 있어 부력 보상을 통한 Feedforward 방식을 이용했다. 부력 보상량은 무게추를 이용해 실제 부력을 측정하여 보상해주었다. 심도 제어의 제어이득은 실험 환경의 제약이 있어 시행착오법을 통해 선정하였다.


3. 파지 작업을 위한 기초 실험

3.1 실험 환경

ROV의 주행 성능 검증을 위해 선박해양플랜트연구소 심해 저집광실험동에서 실험을 진행하였다. 수조의 크기는 폭 6 m, 길이 25 m, 깊이 5 m이며 수심은 약 2.7 m이며 [Fig 7(a)]과 같다. 공급된 물은 민물이며 실내에 설치되어 있기 때문에 바람이나 조류에 의한 외력은 거의 없는 상태이다. [Fig 7(b)]과 같이 실험 중 수중 및 수면에서의 ROV의 상태를 모니터링하기 위해 4대 의 수중 카메라와 1대의 지상 카메라를 설치하였다.

[Fig 7]

Experiment environment

3.2 이동 경로 생성

ROV의 이동경로는 테더의 꼬임을 방지하며 주행할 수 있 도록 설정되어야 한다. 규칙 없는 주행으로 인해 테더가 꼬이 게 되면 ROV에 테더에 손상을 줄 수 있을 뿐만 아니라 테더가 꼬인 상태에서 주행을 계속하게 되면 주행 성능이 떨어져 제 어 불능상태에 이를 수 있다. 이동경로 설정의 또 한 가지 중요 한 점은 목적지 근처에서 물체가 로봇의 시야에서 벗어나지 않게 하기 위해 작업 지점까지 이동할 때 물체와의 Heading 오 차를 줄여가며 접근 할 수 있어야 한다는 것이다. 이를 위해 모 바일 로봇의 자세 안정화 기법(Posture regulation)을 응용하여 이상적인 이동경로를 미리 생성하고 이를 추종하는 방식으로 제어한다[12]. 경로 이동에 사용되는 좌표는 2.3.1절에서 언급 한 관성 항법 정보를 이용한다. [Fig. 8]과 같이 위치 이동을 위 해 아래의 식 (12)-(16)을 이용해 계산된 ROV의 이동속도와 각속도를 기반으로 로봇이 이동해야 할 경로가 계산된다.

[Fig. 8]

Calculation reference path with polar coordinates

r=x2+y2(12) 

γ=atan2(y,x)ψ+π(13 

δ=γ+ψ(14) 

υ=k1r cosγ(15) 

ω=k2γ+k1sinγcosγγ(γ+k3δ),(k1,k2,k3>0)(16) 

여기서 r 은 목적지와 ROV간의 거리, γ는 목적지에서의 목표 Heading과 현재 Heading 간의 오차, δ는 월드 좌표계 x축과 목표 Heading간의 오차, υ는 ROV의 이동속도, ω는 각속도를 의미한 다. 여기서 υω는 ROV의 성능한계를 벗어나지 않게 제한한다.

3.3 실험 결과

실험은 다음과 같은 방법으로 진행하였다. 임의의 좌표에 위치한 로봇이 약 40 초간 시작지점까지 이동하여 대기한다. 이후 70 초간 수조 벽면에 부착되어있는 물체에 접근하는 경 로를 생성하고 이를 추종하여 목표물 근처에 접근하고 약 90 초간 목적지에서 대기하며 정지 상태에서의 위치 및 자세 제 어 결과를 취득하였다. [Fig. 9(a)]은 지상에 설치한 카메라, 수 중에 설치한 카메라, ROV에 장착된 카메라를 통해 획득한 사 진과 항법 정보 바탕으로 Rviz를 통해 가시화한 사진이다. [Fig. 9(b)]에는 경로 추종을 위한 x,y,z, heading의 Reference path를 검정색 선으로, Feedback 데이터를 빨간색 선으로, 목 표 지점을 파란색 선으로 나타내었다. 시작지점에서 목적지까 지 이동할 때 x,y,z, heading의 평균 오차는 각각 15.71 cm, 6.34 cm, 1.61 cm, 1.7° 이며 평균 이동속도는 Surge 기준 평균 9.21 cm/s 속도로 이동함을 관측했다. 제시한 이동 방식은 목 적지에 가까워짐에 따라 경로 계산을 위한 υω가 작아져 목 적지에 도달하는 시간이 현저히 늦어지는 문제가 있다. 이와 같은 단점을 보완하기 약 78 초 부근 r 이 3 m이내일 때 그리고 104초 부근 r이 0.3 m이내일 경우 ROV의 이동 성능을 고려해 이동 속도 υ와 각속도 ω를 조절하였다. 목적지에서 대기 시 x,y,z, heading 평균 오차는 각각 1.01 cm, 0.3 cm, 2.13 cm, 0.84° 이며 이동시보다 안정적인 것을 확인 할 수 있었다.

[Fig. 9]

Result of path tracking experiment. (a) is a video capture and visualization taken during the experiment. (1) was taken from the ground and (2) was taken with an underwater camera mounted on the wall of the tank. (3) shows the result of capturing the inside of the tank using a camera mounted on the ROV. (4) shows the result of the visualization through Rviz, it based on navigation data. (b) is the path tracking control result. The position x,y,z, and heading are controlled, the red line is the navigation feedback data, the black line is the reference to follow, and the black is the position and attitude at the goal.

3.4 고찰

본 실험을 통해 제시한 수중 로봇의 제어 시스템을 기반으 로 정지 상태에서의 운동 제어 성능을 실험을 통해 확인했다. 자세 안정화 기법을 활용한 이동 경로 생성을 통해 ROV는 목 적지까지 접근함에 있어 테더의 꼬임 현상 없이 이동할 수 있 었고 물체 정보 파악을 위해 목적지에 접근할 때 파지 물체와 Heading 오차를 줄여가며 접근할 수 있었다. 이동 경로는 월드 좌표계상의 좌표로 계산되지만 ROV의 운동 좌표계를 월드 좌 표계로 변환함으로써 월드 좌표계상에서 운동 제어됨을 확인 했다. 또한 제어기를 통해 계산되는 6자유도 운동 제어량을 추 력분배 과정을 통해 추진기를 개별제어하지 않고 통합하여 제 어 할 수 있음을 검증했다. 특히 양성 부력을 가지고 있는 로봇의 심도 제어의 경우 정상 상태에서 진동이 발생하거나 정상 상태 오차가 크게 발생하는 문제가 있지만 PD + Feedforward(부력 보 상) 방식의 제어기를 통해 문제를 해결할 수 있음을 검증했다.

현재 계획하고 있는 물체 파지 실험은 로봇의 중심으로부 터 1 m 전방에 물체가 위치할 때 로봇팔을 x축 방향으로만 움 직여 폭이 30 mm 인 물체를 파지하는 것이다. 로봇에 장착한 로봇팔의 Gripper의 폭은 약 130 mm 이다. 로봇이 지면이나 다 른 물체와의 접촉이 없는 정지 상태에서 전방의 물체를 파지 하기 위해서는 Gripper와 물체 사이의 거리가 y축 기준 100 mm 이내의 오차를 유지해야만 파지를 시도할 수 있다. 본 실 험의 목적지에서 로봇이 위치와 자세를 유지하는 상황을 기준 으로 Heading과 위치 y의 평균 오차를 고려했을 때, 물체와 Gripper의 y축 간의 위치 오차는 약 17.88 mm이다. 이는 물체 파지 시도를 할 수 있는 수준의 제어 성능이라고 판단하고 물 체 자율 파지 실험을 계획하고 있다.


4. 결 론

본 논문에서는 수중 자율 작업을 위해 개발 중인 ROV의 제 어 기법과 운용에 필요한 전반적인 기술과 이를 적용한 실험 결과에 대해 설명하였다. 개발 중인 ROV는 수중을 탐사하며 로봇팔을 이용해 수중의 물체를 파지하는데 목적이 있다. 목 적지까지 이동하는 능력, 파지 작업 중 자세를 유지하는 능력, 국소지역을 반복적으로 탐사하는 능력 등이 필요하다. 이를 위해서는 ROV에 장착된 8개의 추진기를 통합하여 효율적인 관리가 필요하며 ROV의 무게중심 및 추진기의 기구학적 배 치를 고려해 추력 분배 행렬을 계산하여 추진기 통합 관리 기 법을 구현하였다. 제시한 방법을 통해 ROV의 위치 및 자세 제 어 수행 능력을 수조 실험을 통해 검증하였다. 또한 ROS를 Middleware로 선정하여 운용 소프트웨어를 구성함으로써 다 수의 센서 및 장비 간 통신이 자유롭게 이루어지게 하고 다수 의 개발자가 동시에 데이터를 처리할 수 있었다.

향후에는 로봇팔이 안정적으로 작업할 수 있는 ROV 위치 및 자세 제어 오차범위를 측정하여 파지 성공 가능성을 판단 하는 알고리즘을 추가하여 수중 물체 자율 파지 실험을 수행 할 것이다. 또한 개발한 기술들과 ROV에 장착된 탐사 장비를 이용한 물체 인식 알고리즘을, 3차원 맵핑 알고리즘[13] 융합하 여 수중 물체를 회수하는 것을 목표로 연구를 진행할 것이다.

Acknowledgments

This research was supported by a grant from Endowment Projects of “Development of Core Technologies for Operation of Marine Robots based on Cyber-Physical System” funded by Korea Research Institute of Ships and Ocean engineering.

References

  • Y.-S. Kim, J.-H. Lee, J.-H. Kim, B.-H. Jun, and P.-M. Lee, “Path Tracking Control Based on RMAC in Horizontal Plane for a Torpedo-Shape AUV, ISiMi,” Journal of Ocean Engineering and Technology, vol. 23, no.6, pp. 146-155, December, 2009.
  • H.-T. Choi, K.-H. Kim, P.-M. Lee, C.-M. Lee, and B.-H. Jun, “Introduction to ROV and Motion Control & Signal Processing for ROV (Remotely Operated Vehicle) Hemire,” Journal of the Korean Society for Precision Engineering, vol. 26, no.5, pp. 41-47, May, 2009.
  • K. Kim, S.-M. Yoon, and C.-M. Lee, “Sea Trial and Performance Analysis of Underwater Light-weight Work Class ROV URI-L,” Conference of The Korean Association of Ocean Science and Technology Societies, Jeju, Korea, 2009.
  • E. Simetti, G. Casalino, F. Wanderlingh, and M. Aicardia, “Task priority control of underwater intervention systems: Theory and applications,” Ocean Engineering, vol. 164, no. 15, pp. 40-54, Sept., 2018. [https://doi.org/10.1016/j.oceaneng.2018.06.026]
  • T. Yeu, H. T. Choi, Y. Lee, J. Chae, Y. Lee, S. S. Kim, S. Park, and T. H. Lee, “Development of Robot Platform for Autonomous Underwater Intervention,” Journal of Ocean Engineering and Technology, vol. 33, no.2, pp. 168-177, April, 2019. [https://doi.org/10.26748/KSOE.2019.021]
  • Y. Lee, Y. Lee, J. Chae, H.-T. Choi, and T.-K. Yeu, “Development of Underwater Laser Scanner with Efficient and Flexible Installation for Unmanned Underwater Vehicle,” Journal of Ocean Engineering and Technology, vol. 32, no.6, pp. 511-517, December, 2018. [https://doi.org/10.26748/KSOE.2018.32.6.511]
  • H. Kang, M.-J. Lee, G. R. Cho, G. Ki, M.-G. Kim, and J.-H. Li, “Development of ROV Trencher URI-T and its Sea Trial,” Journal of Ocean Engineering and Technology, vol. 33, no.3, pp. 300-311, June, 2019. [https://doi.org/10.26748/KSOE.2019.018]
  • ROS.org Documentation, [Online], http://wiki.ros.org/, Accessed: February 06, 2020.
  • T. I. Fossen, Guidance and Control of Ocean Vehicles, Wiley, 1994.
  • J. Garus, “Optimization of Thrust Allocation in The Propulsion System of An Underwater Vehicle,” International Journal of Applied Mathematics and Computer Science, vol. 14, no.4, pp. 461-467, 2004.
  • T. Yeu, Y. Lee, J. Chae, S. Yoon, and Y. Lee, “Experimental Study on Propulsion Characteristic of Autonomous Intervention ROV,” Journal of Ocean Engineering and Technology, vol. 33, no.5, pp. 454-461, October, 2019. [https://doi.org/10.26748/KSOE.2019.064]
  • L. Sciavicco and B. Siciliano, Modelling and control of robot manipulators, Springer Verlag, 2000. [https://doi.org/10.1007/978-1-4471-0449-0]
  • Y. Lee, Y. Lee, H.-T. Choi, and T.-K. Yeu, “Underwater 3D Dense Mapping Using Unmanned Underwater Vehicle with Laser Scanner : First Experiment in Engineering Basin,” Journal of The Institute of Electronics and Information Engineers, vol. 56, no.10, pp. 82-89, October, 2019. [https://doi.org/10.5573/ieie.2019.56.10.82]
이 윤 건

2015 광운대학교 로봇학부(학사)

2017 성균관대학교 기계공학부(석사)

2017~현재 한국해양과학기술원 부설 선박 해양플랜트연구소 연구원

관심분야: 수중 로봇, 수중 항법

이 영 준

2009 충남대학교 메카트로닉스공학과(학사)

2014 충남대학교 메카트로닉스공학과(석사)

2011~현재 한국해양과학기술원 부설 선박 해양플랜트연구부 기술원

관심분야: 수중로봇 자율탐사, 소나 기반 물체 인식, 수중로봇

채 준 보

2014 서울대학교 기계항공공학부(학사)

2014~2017 서울대학교 융합과학기술대학원 (석박통합과정)

2017~현재 한국해양과학기술원 부설 선박 해양플랜트연구소 연구원

관심분야: 매니퓰레이션, 수중로봇

최 현 택

1991 한양대학교 전자공학과(학사)

1993 한양대학교 전자공학과(석사)

2000 한양대학교 전자공학과(박사)

1993~1995 KT 연구개발원 소프트웨어 연구소 전임연구원

2000~2003 미국 하와이 주립대학교 Autonomous System Lab. 후가 박사

2003~현재 한국해양과학기술원 부설 선박해양플랜트연구소 책임연구원

관심분야: 수중로봇, 해양시스템, 강인제어

여 태 경

2003 일본 쿠마모토대학 시스템정보공학부(박사)

2003~2004 쿠마모토대학 시스템정보공학부 객원연구원

2005~현재 한국해양과학기술원 부설 선박 해양플랜트연구소 책임연구원

관심분야: 수중로봇 및 장비 설계, 제어

[Fig. 1]

[Fig. 1]
KRISO Intervention ROV

[Fig. 2]

[Fig. 2]
Software architecture of autonomous driving mode

[Fig. 3]

[Fig. 3]
Coordinate system

[Fig. 4]

[Fig. 4]
Coordinate system transformation for rotational movement when moving position

[Fig. 5]

[Fig. 5]
Configuration of thrusters: (a) shows the configuration of horizontal thrusters and (b) shows the configuration of vertical thrusters. α1-4 means the angle between the horizontal thruster and the y axis of body fixed coordinates. β5-8 means the angle between the vertical thruster and the z axis of body fixed coordinates. d1-8 means the distance between the axis of propulsion and the center of mass.α1-4 =45°, β5-8 =5°, d1 =0.3443 m, d2 =0.4561 m, d3 =0.4619 m, d4 =0.3490 m, d5,8 =0.5027 m, d6,7 =0.4454 m.

[Fig. 6]

[Fig. 6]
System identification in Yaw : (top) Experimental result of step response, (down) Output of identified model

[Fig 7]

[Fig 7]
Experiment environment

[Fig. 8]

[Fig. 8]
Calculation reference path with polar coordinates

[Fig. 9]

[Fig. 9]
Result of path tracking experiment. (a) is a video capture and visualization taken during the experiment. (1) was taken from the ground and (2) was taken with an underwater camera mounted on the wall of the tank. (3) shows the result of capturing the inside of the tank using a camera mounted on the ROV. (4) shows the result of the visualization through Rviz, it based on navigation data. (b) is the path tracking control result. The position x,y,z, and heading are controlled, the red line is the navigation feedback data, the black line is the reference to follow, and the black is the position and attitude at the goal.

[Table 1]

Specification of ROV