Journal of Korea Robotics Society
[ ARTICLE ]
Journal of Korea Robotics Society - Vol. 15, No. 1, pp.16-23
ISSN: 1975-6291 (Print) 2287-3961 (Online)
Print publication date Feb 2020
Received 9 Oct 2019 Revised 10 Dec 2019 Accepted 1 Jan 2020
DOI: https://doi.org/10.7746/jkros.2020.15.1.016

실해역 환경에서 무인 잠수정의 초기 상태 정렬을 위한 GPS와 관성 항법 센서 기반 항법 정렬 알고리즘

김규현1 ; 이지홍 ; 이필엽2 ; 김호성2 ; 이한솔2
GPS and Inertial Sensor-based Navigation Alignment Algorithm for Initial State Alignment of AUV in Real Sea
Gyu-Hyeon Kim1 ; Jihong Lee ; Phil-Yeob Lee2 ; Ho Sung Kim2 ; Hansol Lee2
1Researcher, Mechatronics Engineering, Chungnam National University, Gung-Dong, Youseong-Gu, Daejeon, Korea kgh5111@naver.com
2Researcher, Hanwha Systems, Gumi, Korea hansol.lee@hanwha.com

Professor, Corresponding author: Mechatronics Engineering, Chungnam National University Gung-Dong, Youseong-Gu, Daejeon, Korea ( jihong@cnu.ac.kr)

© Korea Robotics Society. All rights reserved.

Abstract

This paper describes an alignment algorithm that estimates the initial heading angle of AUVs (Autonomous Underwater Vehicle) for starting navigation in a sea area. In the basic dead reckoning system, the initial orientation of the vehicle is very important. In particular, the initial heading value is an essential factor in determining the performance of the entire navigation system. However, the heading angle of AUVs cannot be measured accurately because the DCS (Digital Compass) corrupted by surrounding magnetic field in pointing true north direction of the absolute global coordinate system (not the same to magnetic north direction). Therefore, we constructed an experimental constraint and designed an algorithm based on extended Kalman filter using only inertial navigation sensors and a GPS (Global Positioning System) receiver basically. The value of sensor covariance was selected by comparing the navigation results with the reference data. The proposed filter estimates the initial heading angle of AUVs for navigation in a sea area and reflects sampling characteristics of each sensor. Finally, we verify the performance of the filter through experiments.

Keywords:

AUV, Initial State Alignment, Navigation Algorithm, Inertial Navigation Sensor, GPS

1. 서 론

해양 환경 연구, 수중 자원 탐사, 군사적 정찰 및 임무 수행 등의 목적 달성을 위해 자율 수중 로봇이 활용되고 있으며, 이 에 대한 연구가 활발히 진행되고 있다. 그중 자율형 수중 무인 잠수정인 AUV (Autonomous Underwater Vehicle)는 해양 탐 사 로봇의 핵심 장비이며, 아직도 탐사되지 않은 해양 영역들 을 고려할 때 활용도와 유용성이 매우 높다고 볼 수 있다. AUV 는 수중에 진수되어 잠수하는 시점부터 내장된 항법, 제어시 스템으로 운용이 되기 때문에 넓은 환경에서 탐사 및 임무 수 행이 가능하다. 하지만 특별한 통신 체계가 잡혀 있지 않다면, 운용자와의 통신이 외부적으로 단절되기 때문에 고도의 항법 기술과 자율 제어 기술이 필요하다는 특징이 있다.

일반적인 항법 기술에 사용되는 센서들은 기본적으로 IMU (Inertial Measurement Unit)를 포함한 DVL (Doppler Velocity Log), DCS (Digital Compass), 심도 센서(Depth Sensor) 등을 주 축으로 하며, 위치와 자세를 계산하기 위해 추측 항법(Dead Reckoning)이 사용된다[1,2]. 추측 항법의 경우 운용 시간이 길어 짐에 따라 누적 적분 오차가 발생하여 참값에서 점점 오차가 커 지는 단점이 있다. 이러한 오차를 보상하기 위해 GPS (Global Positioning System)나 소나를 이용한 음향 항법 센서를 통해 측 정된 절대적 위치, 자세 값으로 보정 및 갱신하는 기법들이 존 재한다[3-5]. 이러한 항법 시스템의 기초는 정확한 절대 위치 센 서의 상태 정보(초기 위치, 방향)를 인지하고 있는 상태에서만 성능 발휘 가능하며, 잘못된 초기 상태로 항법이 시작하게 되 면 실제 이동 경로와 크게 틀어져 최악의 경우 잠수정을 회수 하지 못하는 경우가 발생할 수 있다. 따라서 모든 항법 시스템 에 있어서 초기 상태를 파악하는 과정은 필수 불가결하다.

항법 시스템의 초깃값 이란 일반적으로 임무를 시작하기 전 AUV의 6자유도 위치 자세를 말하며, 위치의 경우 기준 좌 표계에서의 AUV의 x, y, z 방향 위칫값을 GPS와 심도계 센서 를 이용하여 절대적으로 측정할 수 있다. 하지만 자세를 따로 측정할 수 없기 때문에 다른 측정 시스템이 필요하다. 기본적인 추측 항법 시스템에 있어서 초기 위치뿐만 아니라 운동체의 초 기 자세는 매우 중요하다. 특히 초기 절대 방위각(real heading) 값은 전체 항법 시스템의 성능을 결정하는 필수적인 요소로 실 제로 초기 방위각 값을 2-3°정도 틀어지게 설정해도 얼마 지나 지 않아 실제 위치에서 크게 벗어나는 것을 확인할 수 있다[6]. 자세 측정에 사용되는 센서는 크게 DCS와 Gyroscope가 있다. 일반적으로 항법 시스템에 사용되는 DCS는 방위각뿐만 아니 라 부착된 센서 기준 roll, pitch 각도도 측정이 가능하기 때문 에 AUV 동체 자세 측정이 가능하다. 하지만 방위각의 경우 주 변 자기장의 영향을 크게 받기 때문에 DCS 값만을 이용하여 AUV의 초기 자세를 특정하기에 무리가 있으며, Gyroscope 역 시 각속도만을 출력하기 때문에 단일 센서로 초기 자세 값을 파악할 수는 없다. 이를 보완하기 위한 개략 정렬 알고리즘으 로 중력 가속도 벡터와 IMU 센서를 이용하여 잠수정의 roll, pitch 각도를 측정하는 방식이 있으나 AUV의 방위각의 경우 정확한 측정이 불가하다[7]. 특히 방위각 값의 경우 절대적인 지 구 좌표계 기준의 진북 방향이 아닌 주변 자기장 영향에 의한 자북 방향각을 출력하는 경우가 많기 때문에 이 값을 사용하기 위해서는 초기 방위각을 산출하기 위한 알고리즘이 필요하다.

따라서 본 논문은 AUV의 방위각을 추정하기 위해 실험적 으로 roll, pitch 각도 값의 변화를 최소화하면서 기본적으로 사 용되는 관성 항법 센서와 GPS만으로 항법을 시작하기 위한 초기 방위각 값을 산출하는 추정기를 제시한다. 추정기는 항 법 알고리즘 연산 결과와 레퍼런스 데이터 비교를 통해 계수 조정을 하며, 항법에 사용되는 기본 필터는 항법 및 다양한 위 치 추정 기법에 사용되고 있는 확장 칼만 필터(EKF: Extended Kalman Filter)를 사용한다. EKF는 비선형 시스템을 선형 시스 템 모델로 선형화하여 추정하는 칼만 필터로 위치 추정의 기 본이 되는 필터이다[8-12].

본 논문이 기여하는 바는 다음과 같다. AUV의 실해역 환경 에서 초기 방위각 값을 정확하게 산출하기 위한 추정 알고리 즘에 대한 내용을 담고 있다. 논문의 구성을 보면 본문의 Ⅱ장 에서는 전체적인 알고리즘의 흐름 및 정렬 알고리즘에 대해 소개하고, Ⅲ장에서 본 알고리즘에 사용된 항법 알고리즘에 대해 소개한다. Ⅳ장에서는 실해역 실험 데이터로 제시한 알 고리즘을 검증하고, 마지막으로 결론 부분에서 결론 및 앞으 로의 연구에 대해 정리하며 끝맺는다.


2. 항법 초기 방위각 정렬 알고리즘

2.1 시스템 및 환경

2.1.1 수중 자율 무인 잠수정

자율 무인 잠수정은 구동부가 추진체(thruster)와 조향타 (rudder), 승강타(elevator)로 이루어진 어뢰형 AUV의 형태를 띠고 있으며 위치 추정뿐만 아니라 제어, 수중 도킹 유도 등 다 양한 분야에서 연구 및 실험이 진행되고 있다[12]([Fig. 1]).

[Fig. 1]

AUV used in research and experiments

2.1.2 좌표계 및 변수 정의

본 논문에서 사용되는 좌표계는 항법 좌표계(navigation frame), 동체 중심 좌표계(body fixed frame) 이다. 항법 좌표계는 항법 시스템이 위치한 곳의 기준 좌표점(navigation system point)에 위치하며, 그 지구 중심 쪽으로 수직한 축을 D축, 진북 방향 벡 터를 N축으로 하고, 동쪽 방향 벡터를 E축으로 하는 좌표계이 다. 동체 중심 좌표계는 항법 시스템이 설치된 운동체의 병진 운동축 surge, sway, heave 방향을 기준 축으로 삼는 좌표계이 다[13]([Fig. 2]).

[Fig. 2]

Relation of navigation frame and body fixed frame

항법 좌표계 기준 동체의 병진, 회전 운동에 대한 6DOF 위 치 자세 및 속도 가속도 표기(notation)는 Fossen 저서의 표기 를 따른다. 병진 운동 상태의 NED 방향 위치와 회전 운동 상태 의 roll, pitch, yaw 방향 오일러 각은 식 (1)로 표현되며 6DOF 는 식 (2)로 표현된다.

η1=[xyz]T,η2=[ϕθψ]T(1) 

η=[η1Tη2T]T(2) 

동체 좌표계 기준 병진ㆍ회전 운동에 대한 동체의 선속도 각속도 성분은 식 (3)-(4)로 표현된다[14].

υ1=[uυw]T,υ2=[pqr]T(3) 

υ=[υ1Tυ2T]T(4) 

위의 기술된 변수에 위 첨자 아래 첨자를 추가하여 좌표계와 기준점을 표시한다. 항법 좌표계(n) 기준 AUV (A)의 6DOF는 ηAn 로 표기한다. 동체 좌표계에서의 동체 속도 및 각속도 υ1b,υ2b 와 항법 좌표계에서의 동체 속도 및 각속도 η˙1n,η˙2n 는 식 (5)-(6) 과 같은 관계를 맺고 있다.

η˙1An=J1(η2An)υ1Ab(5) 

η˙12An=J2(η2An)υ2Ab(6) 

J1(η2An)=[cψcθsψcϕ+cψsϕsψsϕ+cψcϕsθsψcθcψcϕ+sϕsθsψcψsϕ+sθsψcϕsθcθsϕcϕcθ](7) 

J2(η2An)=[1sϕtθcϕtθ0cϕsϕ0sϕ/cθcϕ/cθ](sθ=sinθ,cθ=cosθ,tθ=tanθ)(8) 

2.2 항법 초기 방위각 측정

항법 시스템의 초깃값 이란 일반적으로 임무를 시작하기 전 AUV의 6자유도 위치 자세를 말한다. 위치의 경우 기준 좌 표계에서의 AUV의 x, y, z 방향 위칫값을 GPS와 심도계 센서 를 이용하여 절대적으로 측정할 수 있다. 자세의 경우 roll, pitch 각도 값은 실제 시스템이 켜지는 순간을 기준 각도로 삼 는 DCS의 특성으로 실험적으로 초기화를 진행할 수 있다. 방 위각의 경우는 그렇지 않기 때문에 실제 진북방향 기준 방위 각을 추정하는 추정기가 필요하다. 방위각 추정에 사용되는 센서는 기본적인 관성 항법 센서(IMU, DVL, DCS, 심도 센서) 와 GPS가 사용되며 위 센서들이 출력하는 데이터 및 샘플링 Hz는 [Table 1]과 같다.

Specification of Sensor

실해역 환경의 어뢰형 AUV의 roll, pitch 각도가 0°근처로 실험 환경을 설정한 상태에서 AUV의 초기 방위각은 크게 두 종류로 측정 가능하다. 첫째는 DCS의 Yaw 각도 값이고(a), 둘 째는 GPS를 통해 취득된 AUV의 절대 위치 좌표를 이용한 기 하학 계산을 통해 간접적으로 계산된 값이다(b). GPS에서 측 정된 AUV의 이전 위칫값과 현재 위칫값 좌표 사이의 각도는 AUV가 이동한 위치에 대한 방위각 변화를 나타낸다. 이 값은 모선에 로프로 묶여 있는 상태로 인한 외력이나 주변 해류에 의해 작용하는 편류(drift) 때문에 AUV의 절대 방위각이 될 수 는 없다. 즉, AUV의 실제 방위각은 GPS 방위각에 편류각(drift angle)을 더하여 측정이 되어야 한다. 하지만 실해역에서 AUV 에 작용하고 있는 모든 외란을 고려한 편류각을 우리는 측정할 수 없다. 실험적으로 AUV의 초기 roll, pitch 각도가 0°근처로 임의 설정된 환경이라면, AUV 동체 중심 좌표계 기준의 선속 도 값을 출력하는 DVL의 센서 측정 원리를 이용하여 개략적인 편류각 측정이 가능하다. 측정 원리는 [Fig. 3], [Fig. 4]와 같다.

[Fig. 3]

GPS heading and AUV real heading

[Fig. 4]

DVL vector and AUV drift

하지만 기술한 두 가지 방법은 각각의 센서 특성에 의한 불 확실성을 가지고 있다. DCS는 주변 자기장의 영향을 받아 진 북방향이 아닌 자북방향의 값을 출력하는 불확실성을 가지고 있고, [Fig. 3], [Fig. 4]로 계산된 방식은 GPS와 DLV의 센서 노 이즈에 의해 일정 불확실성을 포함하고 있으며, 특히 GPS 특 성에 의해 가만히 있는 상태에서 그 노이즈가 더 심하다. 또한 DVL 역시 음파가 수신되는 환경에 따라 수신이 되지 않는 환 경이 존재하기 때문에 신뢰성에 문제가 생길 수 있다. 본 알고 리즘을 기술하기 전 기본적인 센서의 성능을 확보하기 위한 실험 환경을 다음과 같이 구성한다.

  1. 정렬은 DVL이 수신되는 해양 환경에서 진행한다.
  2. GPS의 불확실성을 최소화하고자 AUV가 정속 주행을 하 는 환경에서 정렬을 진행한다.
  3. DCS의 기본적인 성능 확보를 위해 정렬은 비교적 지자계 변동이 극심하지 않은 환경에서 진행한다.
  4. 방위각 정렬 구간에서는 주행하는 동안 AUV의 roll, pitch 각도 변화가 최소화되도록 한다.

2.3 확장 칼만 필터를 적용한 방위각 추정 알고리즘

2.3.1 관성 센서 기반 시스템 모델

제안하는 초기 방위각 추정 알고리즘은 EKF를 이용하여 구성된다. 추정하고자 하는 상태 벡터는 AUV의 방위각 Ψ이 다. 현재 시스템은 AUV의 가속도 및 각속도를 측정하는 관성 센서가 탑재되어 있고 이를 이용하여 AUV의 위치 자세를 추 정할 수 있다. 시스템 모델은 IMU의 Gyroscope에서 출력하는 각속도 pI, qI, rI를 이용한 센서 기반 기구학 모델로 구성한다 (식 (9)-(10)).

Ψ^k=Ψ^k1++ΔtΨ˙^k1+(9) 

Ψ˙(t)=qsinϕcosθ+rcosϕcosθ+Q(t)q=wDpI+qI+wNrIr=wEpI-qI+wNrIwN=Ωcos(L)+υERwE=υNRwD=Ωsin(L)υEtan(L)R(10) 

Q는 Gyroscope에서 발생하는 오차 벡터로 백색잡음(white noise)이다. L, , , R, υN, υE, υD는 각각 위도, 경도, 지구 자 전 각속도, 지구 반지름, NED 좌표 기준 동체 속도를 나타낸다.

2.3.2 방위각 측정치 모델

시스템 모델을 보정하여 업데이트해줄 측정 모델치는 2.2 에서 소개한 DCS를 이용한 (a)방식과, GPS와 DVL을 이용한 (b)방식 두 가지가 있다. (a)는 DCS에서 측정된 방위각 Ψ1을 측 정 값으로 사용하며, (b)는 GPS에서 측정된 AUV 좌표 XG,YG 을 통해 계산된 GPS 진로 방향 ψG과 DVL에서 측정된 선속도 기반 2차원 편류각 ψD을 이용하여 식 (11)-(13)과정을 통해 Ψ2 로 계산된다.

Ψ2k=ψGk+ψDk(11) 

ψGk=acos(dYGk|XYGk|)(dXGk|dXGk|)dXGk=XGkXGk1dYGk=YGkYGk1|XYGk|=dXGk2+dYGk2(12) 

ψDk=acos(uDk|uυDk|)(υDk|υDk|)|uυDk|=uDk2+υDk2(13) 

여기서 GPS는 센서의 샘플링 타임이 1Hz로 다른 관성 센서보 다 샘플링이 느리기 때문에 발생하는 샘플링 오차가 있다. 샘 플링이 되지 않는 구간은 수신된 GPS 데이터가 Gyroscope로 보정된 측정치를 사용한다. 측정 벡터는 식 (14)로 정의된다. 식 (15)는 측정방정식을 나타내며, R은 각 측정치의 성능으로 결정되는 공분산 값이다.

zk=[Ψ1kΨ2k+ΔtΨ˙^k1+]T(14) 

z^k=HΨ^k+R(t)(15) 

2.3.3 방위각 추정

EKF는 선형 재귀 필터인 칼만 필터에서 비선형 시스템 추 정을 위해 시스템 모델을 선형화시켜 추정하는 필터로 센서 측정값과 모델 예측값의 비중을 공분산 기반으로 선정하여 추 정 신뢰도를 높인 필터이다. 상태 벡터와 공분산 행렬은 다음 과 같은 과정으로 추정된다[1-8].

P^k=Ak1P^k1+Ak1T+Ak1Gk1QGk1TAk1TΔt(16) 

Kk=P^kHkT(HkP^kHkT+R)1(17) 

Ψ^k+=Ψ^k+Kk(zkHΨ^k)(18) 

P^k+=(IKkHk)P^k(IKkHk)T+KkRKkT(19) 

시스템 측정 모델의 센서 공분산 행렬은 각 방식의 불확실 성 정도를 판단하여 실험적으로 계산된 값을 사용한다. 기준 점으로부터 동일 시간 동안 이동하였을 때 항법 알고리즘으로 계산된 거리 벡터의 크기 α(식 (20))와 실제 레퍼런스 위치로 계산된 벡터의 크기 β(식 (21)), 그리고 항법 위치와 레퍼런스 위치 사이의 벡터의 크기 γ (식 (22))의 관계를 이용하여 레퍼 런스에 대해 항법 데이터가 틀어진 정도를 방위각 공분산으로 사용한다. (a), (b) 두 방식에 대해 각각 진행하며, 각각 동일한 시간동안 항법을 진행하였을 때 측정된 방위각 오차를 공분산 값으로 사용한다.

α=(X0X^k)2+(Y0Y^k)2(20) 

β=(X0XGk)2+(Y0YGk)2(21) 

γ=(X^kXGk)2+(Y^kYGk)2(22) 

δΨ=acos(α2+β2+γ22αβ)(23) 

R=[δΨ1200δΨ22](24) 

추정된 방위각은 항법 알고리즘에 사용되어 AUV의 6자유 도 위치, 자세를 추정하는 데 사용된다. 전체적인 항법 시스템 구조는 [Fig. 5]와 같다.

[Fig. 5]

Routine of whole navigation system


3. 항법 알고리즘

본 절에서는 앞 절에서 계산된 방위각을 통해 AUV의 위치 자세를 추정할 항법 알고리즘을 기술한다. 기본적으로 관성 항 법 센서인 IMU 센서의 가속도와 각속도 u˙I,υ˙I,w˙I,pI,qI,rI 을 기반으로 AUV의 위치와 자세를 추정한다. 상태 방정식과 측정 방정식은 식 (25)-(26)와 같다.

X˙(t)=f(X(t),u(t))+w(t),wN(0,q)(25) 

z(t)=HX(t)+r(t)(26) 

본 AUV의 자세를 추정하는 필터의 시스템 구성은 다음과 같다. 위치와 자세를 나누어 추정하였으며 동일한 EKF를 사용 하였기 때문에 필터 수식을 제외한 시스템 모델과 측정 벡터만 기술한다. 자세 추정 모델의 경우 식 (27)-(29)와 같다. L, , , R은 각각 위도, 경도, 지구 자전 각속도, 지구 반지름을 나타낸다.

X=[ϕAnθAnψAn]T(27) 

z(t)=[ϕDCSθDCS]T(28) 

X^k=X^k1++ΔtX˙^k1+ϕ˙=p+qsinϕtanθ+rcosϕtanθθ˙=qcosϕrsinϕψ˙=qsinϕcosθ+rcosϕcosθp=pI+wDqIwErIq=wDpI+qI+wNrIr=wEpIwNqI+rIwN=Ωcos(L)+υERwE=υNRwD=Ωsin(L)υEtan(L)R(29) 

AUV의 위치 추정 모델과 측정 벡터의 경우 식 (30)-(32)와 같다. 여기서 g는 중력 가속도를 나타낸다.

X=[η1Anυ1Ab]T=[xAnyAnzAnuAbυAbwAb]T(30) 

z(t)=[zDpudυlυdυlwdυl]T(31) 

X^k=X^k1++ΔtX˙^k1++12Δt2X¨^k1+(32) 

x˙=ucθcψ+υ(sϕsθcψcϕsψ)+w(cϕsθcψ+sϕsψ)y˙=ucθsψ+υ(sϕsθsψ+cϕcψ)+w(cϕsθsψsϕcψ)z˙=usθ+υsϕcθ+wcϕcθx¨=u˙cθcψ+υ˙(sϕsθcψcϕsψ)+w˙(cϕsθcψ+sϕsψ)y¨=u˙cθsψ+υ˙(sϕsθsψ+cϕcψ)+w˙(cϕsθsψsϕcψ)z¨=u˙sθ+υ˙sϕcθ+w˙cϕcθu˙=u˙imu2ΩυEsin L+υNυDυE2tan(L)Rυ˙=υ˙imu+2Ω(υNsin L+υDcos(L))+υE(υD+υNtan(L))Rw˙=w˙imu2ΩυEcos LυE2+υN2R+g


4. 실해역 실험

4.1 실험 환경

본 장에서는 제시한 알고리즘의 성능을 실제 시스템을 통 한 실험으로 검증한다. 실험은 거제도 장목항 한국해양과학기 술원 남해연구소 앞 인근 해역에서 진행하였다([Fig. 6]).

[Fig. 6]

Environment of experiment

4.2 실험 방식

실험은 진수된 AUV와 연결된 수상선을 운용하여 AUV를 이동시키는 것으로 진행하였으며, 크게 ‘센서 동작 체크 및 공 분산 측정–초기 방위각 추정을 통한 정렬–항법’의 3단계로 구 성된다. 검증은 AUV를 진수 후 직접 운용하면서 취득한 데이 터와 레퍼런스인 GPS 데이터를 비교하여 항법 성능 및 알고 리즘 성능을 확인하였다. 처음 방위각 정렬을 위한 공분산 측 정 구간과 방위각 정렬 알고리즘이 동작할 동안은 노끈과 사 람이 잠수정의 roll, pitch 자세를 고정한 상태에서 진행하였으 며, 정렬이 끝난 구간부터는 자세 고정을 풀고 사용자에 의해 항법 단계로 넘어가 AUV를 운용한다. 성능은 GPS 데이터를 레퍼런스로 하여 항법 구간에서의 최대 오차 및 오차 퍼센트 를 확인하는 것으로 진행하였다.

4.3 실험 결과

좌표계는 GPS를 통해 얻은 출발 지점의 위치를 기준으로 UTM좌표계(Universal Transverse Mercator Coordinate System) 로 변환한 뒤, 출발 지점을 (0,0)좌표로 조정한 좌표계를 사용 하였다. [Fig. 7]은 항법 결과를 나타낸다. 파란색 데이터는 GPS 데이터이고, 붉은색 데이터는 항법 결과이며, 항법 시스 템의 단계별로 진행되고 있는 상태를 나타내고 있다. step 1 구 간에서 먼저 DCS 방위각으로 항법을 진행하였을 때 방위각 공분산을 확인한 뒤, step 2 상태에서는 GPS, DVL, Gyro를 이 용한 방위각의 공분산을 확인한다. step 1과 step 2가 진행되는 시간은 같다. step 3 부터는 확인한 공분산 값을 기준으로 방위 각 정렬 필터가 동작하여 방위각을 추정한다. 그 후 추정된 방 위각으로 항법을 진행한다.

[Fig. 7]

Experiment result of the navigation and alignment algorithm and each step

[Fig. 8]는 전체 운용 결과를 나타내는데, (a)는 방위각 정렬 알고리즘을 적용하지 않고 장착된 DCS로 실험을 진행하였을 때를, (b)는 제시한 정렬 알고리즘을 적용하였을 때의 결과를 나타낸다. 결과를 보면 레퍼런스 데이터인 GPS의 위치에 맞 게 방위각이 정렬되어 항법을 진행하는 것을 볼 수 있다. [Fig. 9]는 (a)(b)의 실시간 거리 오차를 나타낸다. 실험 결과 정렬 을 하지 않았을 때 오차가 점점 커지는 것을 확인할 수 있다. 제 시한 알고리즘을 적용하지 않았을 때는 최대 거리 오차가 9 m 까지 측정되지만 제시한 알고리즘을 적용하였을 때 최대 거리 오차가 2.2 m 내외로 수렴하는 것을 확인할 수 있다. 처음 오차 가 0 m로 표시된 부분은 정렬이 진행 중인 상태이다.

[Fig. 8]

Experiment result of the AUV navigation path and GPS reference path

[Fig. 9]

Real time error of estimated navigation result about two case which is aided alignment and un aided alignment


5. 결 론

본 논문은, 복잡한 실해역 환경에서 AUV의 초기 방위각 값을 정확하게 추정하기 위한 연구로, 실험적 구속 조건과 주 어진 센서 환경과의 타협점을 통해 방위각을 추정하는 방법 을 제시하였다. 알고리즘은 기본적으로 사용되는 관성 항법 센서와 GPS로 구성하였으며, 관성항법 센서와 GPS의 샘플 링 조건도 고려가 되었다. 제시한 알고리즘은 해상 실해역 실 험을 통해 알고리즘의 유효성을 검증하였다. 추후 연구가 진 행된다면 더 능동적이고 복합적인 환경에서도 제한 없이 적 용할 수 있도록 정렬 알고리즘을 설계하는 연구가 진행되어 야 할 것으로 보인다. 본 논문에서 제시한 알고리즘은 AUV를 비롯한 무인 수중 운동체의 수중 항법 시스템에 도움이 될 것 으로 판단된다.

References

  • P.-M. Lee, H. Shim, H. Baek, B. Kim, J.-Y. Park, B.-H. Jun, and S.-Y. Yoo, “Navigation System for a Deep-sea ROV fusing USBL, DVL, and heading measurements,” Journal of Ocean Engineering and Technology, vol. 31, no. 4, pp. 315-323, Aug., 2017. [https://doi.org/10.26748/KSOE.2017.08.31.4.315]
  • C.-M. Lee, P. M. Lee, and W.-J. Seong, “Underwater Hybrid Navigation Algorithm Based on an Inertial Sensor and a Doppler Velocity Log Using an Indirect Feedback Kalman Filter,” Journal of Ocean Engineering and Technology, vol. 17, no. 6, pp. 83-90, Dec., 2003.
  • P.-M. Lee, B.-H. Jeon, S.-M. Kim, C.-M. Lee, Y.-K. Lim, and S.-I. Yang, “A hybrid navigation system for underwater unmanned veh icles, using a range sonar,” Journal of Ocean Engineering and Technology, vol. 18, no.4, pp. 33-39, Aug., 2004.
  • S.-H. Mok, H. Bang, J. Kwon, and M. Yu, “Terrain referenced navigation for autonomous underwater vehicles,” Journal of Institute of Control, Robotics and Systems, vol. 19, no.8, pp. 702-708, Aug., 2013. [https://doi.org/10.5302/J.ICROS.2013.13.9017]
  • S.-H. Mok, H. Bang, and M. Yu, “Performance Analysis of Vision-Based Terrain Referenced Navigation,” Journal of Institute of Control, Robotics and Systems, vol. 23, no.4, pp. 294-299, Apr., 2017. [https://doi.org/10.5302/J.ICROS.2017.16.0196]
  • S.-G. Park, D.-H. Hwang, and S. J. Lee, “Psi angle error model based alignment algorithm for strapdown inertial navigation system,” Journal of Institute of Control, Robotics and Systems, vol. 17, no. 2, pp. 183-189, Dec., 2011. [https://doi.org/10.5302/J.ICROS.2011.17.2.183]
  • H.-S. Kang, S.-M. Hong, J.-N. Sur, and J.-Y. Kim, “Design of GPS-aided dead reckoning algorithm of AUV using extended Kalman Filter,” Journal of Ocean Engineering and Technology, vol. 31, no. 1, pp. 28-35, Feb., 2017. [https://doi.org/10.5574/KSOE.2017.31.1.028]
  • Y.-S. Park, W.-S. Choi, S.-I. Han, and J.-M. Lee, “Navigation system of UUV using multi-sensor fusion-based EKF,” Journal of Institute of Control, Robotics and Systems, vol. 22, no. 7, pp. 562-569, Jun., 2016. [https://doi.org/10.5302/J.ICROS.2016.15.0213]
  • I. Yun, J. Shim, and J. Kim, “Pose estimation method using sensor fusion based on extended Kalman Filter,” Journal of The Institute of Electronics and Information Engineers, vol. 54, no. 2, Feb., 2017.
  • T.-S. Yoo and M. H. Kim, “Analysis of integrated navigation performance for sensor selection of Unmanned Underwater Vehicle (UUV),” Journal of Ocean Engineering and Technology, vol. 28, no.6, pp. 566-573, Dec., 2014. [https://doi.org/10.5574/KSOE.2014.28.6.566]
  • C.-W. Kang, C.-G. Park, and Y. M. Yoo, “Performance improvement of attitude estimation using modified euler angle based Kalman Filter,” Journal of Institute of Control, Robotics and Systems, vol. 14, no.9, pp. 881-885, Sept., 2008. [https://doi.org/10.5302/J.ICROS.2008.14.9.881]
  • G.-H. Kim, J. Lee, P.-Y. Lee, H. S. Kim, and H. Lee, “A Study on Docking Guidance Navigation Algorithm of AUV by Combining Inertial Navigation Sensor and Docking Guidance Sensor,” Journal of Institute of Control, Robotics and Systems, vol. 25, no.7, pp. 647-656, Jul., 2019. [https://doi.org/10.5302/J.ICROS.2019.19.0089]
  • D. H. Titterton and J. L. Weston, Strapdown Inertial Navigation Technology, 2nd ed. IET, 2004. [https://doi.org/10.1049/PBRA017E]
  • T.I. Fossen, Guidance and Control of Ocean Vehicles, John Wiley & Sons Inc., 1994.
김 규 현

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

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

관심분야: 항법, 수중 로봇, 양팔 로봇, 로봇 위치 추정

이 지 홍

1983 서울대학교 전자공학과(공학사)

1985 한국과학기술원 전기 및 전자공학과 (공학석사)

1991 한국과학기술원 전기 및 전자공학과 (공학박사)

1994~현재 충남대학교 메카트로닉스공학과 교수

관심분야: 로봇 위치 추정, 수중 로봇, 양팔 로봇, 야지 주행 로봇

이 필 엽

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

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

2006~2008 한국해양연구원/해양시스템 안전연구소 연구사업인력

2008~2011 한국해양연구원/해양시스템 안전연구소 단위사업인력

2011~2016 (주)한화종합연구소 무인화센터 선임연구원

2016. 11.~현재 한화시스템 해양시스템2팀 수석연구원

관심분야: 수중로봇, 자율무인잠수정, 항법, 제어, 모니터링 시스템

김 호 성

2009 한국해양대학교 기계시스템(공학사)

2011 한국해양대학교 기계공학(공학석사)

2011. 2.~현재 한화시스템

관심분야: 수중로봇, 자율무인잠수정, 항법, 제어

이 한 솔

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

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

2018. 3.~현재 한화시스템.

관심분야: 수중로봇, 자율무인잠수정, 항법, 제어

[Fig. 1]

[Fig. 1]
AUV used in research and experiments

[Fig. 2]

[Fig. 2]
Relation of navigation frame and body fixed frame

[Fig. 3]

[Fig. 3]
GPS heading and AUV real heading

[Fig. 4]

[Fig. 4]
DVL vector and AUV drift

[Fig. 5]

[Fig. 5]
Routine of whole navigation system

[Fig. 6]

[Fig. 6]
Environment of experiment

[Fig. 7]

[Fig. 7]
Experiment result of the navigation and alignment algorithm and each step

[Fig. 8]

[Fig. 8]
Experiment result of the AUV navigation path and GPS reference path

[Fig. 9]

[Fig. 9]
Real time error of estimated navigation result about two case which is aided alignment and un aided alignment

[Table 1]

Specification of Sensor