
수중로봇의 정밀한 위치추정을 위한 USBL 사용 운항 중 헤딩 보정방법
CopyrightⓒKROS
Abstract
This paper proposes a method to perform continuous alignment during navigation by utilizing USBL position and the ICP algorithm to enhance the navigation performance of safety-support robots for underwater leisure activities. Conventional underwater navigation using USBL typically employed fusion methods based on INS (Inertial Navigation System) and Kalman filtering. However, the conventional fusion method using the Kalman filter causes unexpected position changes whenever USBL positioning data are received. This can adversely affect control for autonomous navigation. Moreover, inertial navigation systems without additional alignment processes after initial alignment significantly degrade the accuracy of fusion-based navigation when the initial heading estimation is inaccurate. To solve these issues, this paper proposes a method to continuously calculate and correct heading offsets during navigation by using USBL position and INS position after the initial alignment. The experimental results demonstrated that the navigation accuracy improved by up to 75.49% compared to the existing method. Additionally, the method was shown to enhance navigation performance even with reduced initial alignment time due to the continuous alignment process during navigation.
Keywords:
USBL System, INS, Initial Alignment, ICP Algorithm, Underwater Navigation1. 서 론
최근 국내에서는 스쿠버 다이빙에 대한 관심과 참여자가 증가하고 있으나 스쿠버다이빙 중 발생할 수 있는 여러 위험(열 손실, 질소 마취, 이산화탄소 축적 등)으로 인한 다양한 안전사고 또한 증가하고 있다[1,2]. 본 연구진들은 위와 같은 위험을 최소화하고 스쿠버 다이버의 안전한 다이빙활동을 위하여 [Fig. 1]과 같은 가이드용, 구조용 안전지원 로봇을 개발하고자 한다.
개발 중인 안전지원로봇은 다이버의 안전지원을 위해 다이버 주변 1 m 이내 접근 지원이 가능하도록 자율운항 및 자율제어 알고리즘이 개발되고 있으며 AI를 기반으로 다이버의 상태를 인식하여 다이버가 의식이 없다고 판단할 경우 다이버를 견인 및 구조할 수 있도록 개발 중에 있다. 이러한 임무 수행을 위해선 정밀한 자세 및 위치 정보를 추정하는 것이 중요한데, 일반적으로 관성항법시스템(Inertial Navigation System, INS)과 USBL (Ultra-Short BaseLine) 시스템이 사용된다[3]. 관성항법은 우수한 단기 정확도, 빠른 위치추정 등의 장점이 있으나[4], 표류오차가 발생할 수 있고 초기헤딩이 부정확할 경우 실제 위치 사이의 오차는 크게 증가한다[5]. USBL (Ultra-Short BaseLine)은 음파를 통해 수중로봇과의 상대적인 위치를 획득하기 때문에 표류오차가 없으나, Transceiver와 Transponder의 거리에 따라 데이터 획득 주기가 길어지며 수중에서 음파의 회절, 다중반사와 같은 원인으로 인해 아웃라이어(Outlier) 또는 결측 값이 발생할 수 있다[6].
이러한 두 시스템의 한계점을 보완하기 위해 IMU (Inertial Measurement Unit), DVL (Doppler Velocity Log) 등의 항법센서를 이용한 관성항법 추정위치와 USBL 위치 정보를 EKF (Extended Kalman Filter) 또는 파티클 필터(Particle Filter)를 사용해 융합한 연구가 진행된 바 있다[7-9]. 그러나 USBL의 위치의 정확도는 GPS와 비교해 불확실성이 크고 수신 주기 또한 비교적 불규칙 하기 때문에 USBL이 수신될 때마다 이전 스텝의 위치와 비교하여 로봇의 위치 변화가 크게 발생할 수 있고 이는 자율운항을 위한 제어에도 영향을 미칠 수 있다. 따라서 본 논문은 이러한 문제를 해결하기 위해 기존연구들과 달리 두 위치정보(관성항법 추정위치, USBL 위치)를 이용해 운항 중 지속적으로 로봇의 헤딩을 보정하여 항법 성능을 향상시키는 방법을 제안하고자 한다.
위치정보를 이용해 로봇의 헤딩을 보정하는 방법에 대한 선행연구는 다양하게 연구되었는데, GPS 위치와 DVL의 속도 벡터를 이용해 초기 헤딩 바이어스를 추정하는 초기정렬 방법[10]과 원점으로부터 GPS 위치와 관성항법 추정위치 사이각을 산출 후 wiener 필터를 이용해 보정값을 산출하는 방법[11,12] 이 연구되었다. 또한 ICP 알고리즘과 두 위치정보(GPS, 관성항법 추정위치)를 이용한 보정값 산출방법이 연구된 바 있다. 본 논문에서 제안하는 방법은 앞서 언급한 선행연구인 위치정보를 이용한 헤딩 보정방법[11]을 기반으로 설계되었으나 GPS 위치 대신 수중에서 USBL 위치 정보를 사용하는 것과 운항 초기에만 진행하는 것이 아닌 운항 중 지속적으로 헤딩 보정을 진행하는 차이가 있다. 또한 선행연구[11,12]의 정렬과정에서는 정밀한 보정값 산출을 위해 직진기동을 실시 하지만 본 연구에서는 수중에서 다양한 기동을 진행하는 중 정렬을 진행하기 위해 ICP 알고리즘을 이용하여 헤딩 보정값을 산출한다. 제안한 방법은 실해역에서 취득한 데이터를 MATLAB 시뮬레이션을 이용해 기존 관성항법만을 이용한 위치 추정결과와 제안한 알고리즘을 적용한 항법 알고리즘의 위치 추정결과를 비교하여 성능을 검증한다. 본 알고리즘을 통해 기대하는 효과는 다음과 같다.
- 1. USBL 수신 시 급격한 위치변화 방지
- 2. 초기헤딩 추정을 위한 초기정렬 이후 추가적인 정렬을 통해 초기정렬의 성능 보완
- 3. 수중에서의 정렬과정으로 인해 신속한 정렬을 위한 초기정렬 시간 단축 가능
본 논문의 구성은 Ⅱ장에서 USBL의 아웃라이어 제거방법 및 본 논문에서 제안하는 알고리즘에 대해 소개한다. Ⅲ장에서는 제안한 알고리즘을 실해역에서 취득한 데이터로 검증하고 마지막으로 IV장에서는 실험 결과에 대한 결론과 추후 연구에 대한 내용으로 마무리를 맺는다.
2. USBL 전처리 및 헤딩 보정값 산출
2.1 USBL Outlier 제거
USBL은 음파를 사용하는 센서 특성 상 다양한 원인으로 인해 블랙아웃과 아웃라이어가 발생하며 발생 빈도가 높다[13]. 블랙아웃의 발생하는 원인은 장애물(선체, 암반, 해조류 등)에 의해 음향 신호가 차단되거나 흡수되는 경우에 발생하며 아웃라이어는 음파의 회절, 바닥 및 해저 구조물로 인해 신호가 여러 번 반사되는 다중반사 와 수신기에 신호가 여러 경로로 도달하는 다중 경로 간섭(multi path) 등이 있다. 특히 스쿠버 다이버들이 활동하는 수중 환경에서는 해저 구조물들이 많아 위와 같은 현상이 발생할 확률이 높다. [Fig. 2], [Fig. 3]의 (a)은 블랙아웃과 아웃라이어가 발생한 모습을 보여준다. 이러한 블랙아웃과 아웃라이어에 대해 정확한 위치 정보를 얻기 위해 여러 선행연구들이 진행되었는데 중앙값과 현재 위치데이터 사이의 거리가 임계값 초과 시 아웃라이어 로 간주하는 방법[14], 마할라노비스 거리(Mahalanobis distance)를 이용한 제거방법[15], USBL 위치를 특징점으로 하는 보로노이다이어그램(Voronoi Diagram)을 생성하여 이동하는 평균점이 속하지 않은 보로노이셀의 특징점을 아웃라이어로 판단하는 방법[13] 등이 연구된 바 있다. 그러나 기존 연구들은 슬라이딩 윈도우(sliding window)를 사용하기 때문에 짧은 시간에 연속적으로 발생하는 아웃라이어가 윈도우 크기의 절반 이상을 차지하게 되면 전체적인 아웃라이어 감지 능력이 떨어질 수 있으며 보로노이다이어그램을 이용하는 방법의 경우는 윈도우의 평균점의 위치와 가까운 USBL 위치를 판별하기 때문에 최신 위치데이터에 대해서는 즉각적인 판별이 어렵다는 단점이 있다. 따라서 본 논문은 USBL 데이터 수신 시 즉각적인 판별과 지속적인 아웃라이어에 강인한 수중로봇의 속도를 기반으로 한 아웃라이어 제거방법을 사용한다.
먼저 USBL 데이터 취득 시 로봇이 잠수하기 전에 취득되어 발생한 아웃라이어가 있기 때문에 안정적인 USBL 위치데이터 수신을 위해 약 3 m 이상의 수심에서 취득된 데이터만을 판별한다. 이후 식 (1)을 이용하여 k - n스텝에서 취득한 아웃라이어가 아닌 직전 USBL 수신위치 (, )와 k스텝에서 수신된 최신위치 (, ) 사이의 거리(d)가 식 (2), (3)으로 산출할 수 있는 두 위치데이터의 수신 주기(ΔtUSBL)동안 수중 로봇의 이동 속도를 고려해 최대로 이동할 수 있는 거리(dmax)보다 큰 경우 아웃라이어로 판별한다. 이때 dmax은 수중 로봇이 Δt동안 이동 중 관성항법으로 추정한 항법 좌표계의 X, Y방향 속력의 최대값(vXmax, vYmax)을 이용해 산출하며 발생할 수 있는 오차를 감안하여 실험적으로 산출한 20%의 오차를 더하여 산출한다.
아웃라이어가 아닌 최초의 USBL 위치 판별은 관성항법 추정 위치와의 거리를 이용한다. 전체적인 운항 과정에서 관성항법 추정위치의 정확도는 초기정렬 완료 후 가장 높다. 따라서 초기정렬 후 잠수하여 초기에 수신된 USBL 위치와 관성항법 위치의 차이가 센서 정확도 내에 존재하는 경우 아웃라이어가 아닌 최초의 위치로 판정한다. 본 연구에서 사용한 USBL은 Sonardyne 사의 ‘HPT 3000’ 모델로 제조사에서 제공하는 데이터시트에 따르면 슬랜트 거리(slant rage)의 0.9%를 표준편차(1σ)로 산출한다. 여기서 슬랜트 거리는 Transceiver와 Transponder 사이의 거리를 의미하는데 이를 바탕으로 3시그마 규칙을 적용하여 관성항법 추정위치와 USBL 수신 위치 사이의 거리가 슬랜트 거리의 2.7% 이내 일 경우 아웃라이어가 아닌 최초의 위치로 판정한다. 3시그마 규칙은 평균을 기준으로 표준편차의 3배 범위에 거의 모든 값(99.7%)을 의미하며 이를 벗어나는 데이터는 이상치로 판별할 수 있다. 본 방법을 사용하여 아웃라이어 제거 전, 후를 비교한 결과는 [Fig. 2], [Fig. 3]와 같다.
| (1) |
| (2) |
| (3) |
2.2 USBL 수신 delay 보정
본 논문에서 제안한 알고리즘에서 ICP 알고리즘을 사용하기 위해서는 USBL 위치데이터와 동일 측정지점에서 산출된 관성항법 추정위치가 필요하다. 그러나 USBL을 이용한 수중 음향 거리 측정 과정에서 지연 문제가 발생한다[16]. 이는 Transceiver와 Transponder 사이의 거리가 증가함에 따라 발생하며 수중로봇의 위치추정에 USBL 위치를 이용하려면 이를 음향 모뎀을 통해 전달해야 하는데, 이 과정에서도 상당한 지연이 발생할 수 있다[17]. 따라서 지연문제를 해결하고 USBL 위치정보와 동일 수신지점에서의 관성항법 추정위치를 산출하기 위해 [Fig. 4]과 같은 거리기반 지연보정 방법을 제안한다.
먼저 USBL 위치의 측성 시점과 관성항법 시점이 일치한다면 두 위치사이의 거리 오차도 적을 것이라는 가정을 전제로 한다. k스텝에서 수신된 최신 USBL 위치가 수신되었을 때 이전 수신된 USBL 수신 시점 사이에 산출되었던 관성항법 추정위치들 중 USBL 위치와 거리오차가 최소가 되는 관성항법 추정위치를 k스텝에서의 USBL 위치와 동일 시점에 산출된 위치로 판정하여 버퍼에 저장된다. 이후 각 위치들은 헤딩보정을 위한 ICP 알고리즘의 두 점군으로 활용된다. [Fig. 5]는 제안방법을 통해 USBL 위치와 동일 시점에 산출된 위치로 판정된 관성항법 추정 위치를 나타낸다.
2.3 ICP 이용 헤딩 보정
서론에서 언급한 바와 같이 본 논문에서 제안하는 헤딩 보정 방법은 선행 연구인 위치기반 초기정렬을 기반으로 한다. 선행 연구에서는 GPS 수신 위치와 항법 알고리즘 추정위치를 통해 헤딩 오차를 산출하는 방법이 연구되었고, 최종 헤딩 오차 산출 방법에 따라 wiener 필터를 이용한 방법[11,12]과 ICP를 이용한 방법 등이 연구된 바 있다. wiener 필터를 이용한 방법의 경우 정밀한 정렬을 위해 초기정렬 과정 중 직선기동을 필요조건으로 한다[11]. 하지만 수중에서 다이버와 함께 기동하는 지원로봇은 보다 자유로운 기동이 가능해야 한다. 따라서 직선 이동의 필요 조건 없이 수행 가능한 ICP 알고리즘을 이용하여 헤딩 보상값을 산출한다.
ICP 알고리즘은 주로 point cloud 간 정합에 사용되는 알고리즘으로. 서로 다른 두 점군에서 각각의 대응되는 점의 거리를 최소화하기 위한 회전 및 평행 이동 행렬을 산출할 수 있다. 두 점군을 USBL 위치와 항법 알고리즘 추정 위치로 하는 경우 ICP 알고리즘을 이용해 두 점군에 대한 회전변환 행렬을 산출할 수 있으며, 이 회전변환의 회전각은 헤딩 보정값으로 사용할 수 있다. ICP 알고리즘을 이용해 헤딩 보정값을 산출하는 방법은 아래 [Fig. 6]와 수식 (4)-(7)과 같다. 우선 두 점군 (PUSBL, PNavi)의 질량중심(center of mass) (, )를 일치시킨다. 이후 대응되는 점들 사이의 거리가 최소가 되도록 점군을 회전시킨다. 이때 회전행렬은 SVD (Singular Value Decomposition)을 통해 산출이 가능하다.
| (4) |
| (5) |
| (6) |
| (7) |
앞서 언급한 ICP 알고리즘을 통해 산출한 헤딩 보정값을 이용하여 헤딩을 보정과정은 [Fig. 7]과 같고 전제적인 진행 구조는 [Fig. 8]과 같다. 먼저 본 과정은 수상에서 초기정렬을 진행한 이후 수중에서 기동하면서 진행되는데, 수중에서 아웃라이어가 아닌 USBL 위치와 동시점의 관성항법 추정 위치가 20샘플이 수집되면 ICP 알고리즘을 통해 헤딩 보정값(ψoffset) 산출하고 이를 로봇의 기존 헤딩에 더하여 로봇의 헤딩을 보정한다. 이후 슬라이딩 윈도우를 이용하여 USBL 수신 시마다 보정값 산출을 지속한다. 산출된 보정값은 급격한 헤딩 변화를 방지하기 위해 가중치(W)가 곱해져 기존 헤딩에 더해진다. 샘플 개수의 경우 선행연구인 위치기반 초기정렬의 샘플 수인 20개를 기준으로 다양한 샘플크기(10, 20, 30, 40개 등)에 대해 성능을 비교하여 위치추정 결과가 가장 안정적인 샘플 개수 20개로 선정하였다.
헤딩 보정값 산출은 아웃라이어가 아닌 USBL 위치가 수신될 때마다 진행되는데, 산출된 보정값을 그대로 보정할 경우 [Fig. 9]과 같이 큰 헤딩변화를 야기하며 부정확한 헤딩 보정이 진행된다. 이러한 현상은 슬라이딩 윈도우 내에 1개 샘플의 위치가 업데이트 되어도 윈도우 내에 19개의 샘플의 위치 변화가 없기 때문에 ICP 알고리즘을 이용해 산출한 보정값이 직전 보정값과 유사하고 이를 그대로 보정하면 한, 두 샘플 업데이트 만에 중복된 보정값이 누적되어 헤딩이 한 방향으로 회전하여 발생한다. 따라서 가중치를 이용해 점진적인 헤딩 보정을 진행해야 한다. 점진적인 보정을 위한 가중치는 윈도우 크기의 역수(0.05)를 기준으로 USBL 위치의 오차로 인해 발생할 수 있는 보정값 오차 등을 고려하고, 여러 실해역 데이터를 이용해 실험적으로 산출한 0.01을 사용하였다.
3. 실험 및 실험결과
3.1 실험 구성
본 장에서는 제안한 알고리즘의 성능을 검증하기 위해 [Fig. 10]과 같이 실해역 실험을 통해 취득한 2개의 데이터셋을 이용하여 실험을 진행하였다. 센서데이터 취득을 위한 실해역 실험은 거제시에 위치한 한국해양과학기술원 남해연구소 앞 해역에서 수행되었으며, 수중로봇의 GPS를 이용한 초기정렬를 위해 수상기동을 한 후 수중으로 잠수하여 약 6~7 m 수심에서 USBL 위치정보를 취득하였고 일정 시간 기동 후 다시 수상으로 부상해 경로 끝점의 GPS 정보를 취득하는 방식으로 진행되었다. USBL의 Transceiver의 경우 남해연구소 앞 해역 연안의 폰툰 구조물에 설치하여 실험을 진행하였다. 데이터셋의 운용 거리와 운용 시간에 대한 정보는 [Table 1]과 같다.
실험은 총 3가지 방법으로 수행되었으며 다음과 같다.
- (a) 선행연구의 사용된 관성항법 알고리즘만을 사용하는 방법
- (b) 제안하는 방법을 적용한 USBL 융합항법을 사용한 방법
- (c) 제안하는 방법에서 초기정렬 시간을 10초로 단축한 방법의 항법 결과를 비교하였다.
초기정렬은 이전 연구와 동일 한 wiener 필터를 사용한 방법을 사용하였고 관성항법 역시 선행연구[11]의 알고리즘을 동일하게 사용하였다.
3.2 실험 결과
[Fig. 11]~[Fig. 16]는 앞서 언급한 3가지 방법을 각 데이터 셋을 이용해 실험한 위치 추정 결과로 먼저 [Fig. 11], [Fig. 14]은 기존 관성항법만을 사용한 방법(a)의 위치추정 결과이며, [Fig. 12], [Fig. 15]는 제안방법을 적용한 방법(b)의 위치추정 결과이고 먼저 [Fig. 13], [Fig. 16]는 제안방법에서 초기정렬을 10초로 단축한 방법(c)의 위치추정 결과이다. (a), (b)의 경우 모두 초기정렬을 선행연구와 동일하게 20초간 진행하였다. [Table 2], [Table 3]은 GPS와 항법 알고리즘 추정 위치 사이의 끝점 거리 오차와 USBL 위치와 항법 알고리즘 추정 위치 사이의 평균 거리 오차를 나타낸다. 실험 결과 두 데이터 셋 모두 기존의 관성항법만 사용한 방법보다 제안방법인 USBL을 이용한 지속적인 헤딩 보정을 적용한 방법이 비교적 개선된 결과를 나타냄을 확인하였으며, 방법 (c)의 경우 초기정렬 시간이 단축되어도 20초간 초기정렬을 진행한 방법(b)와 유사한 위치추정 결과를 확인하였다. [Table 4]와 같이 끝점오차는 방법(b)의 경우 기존 방법인 (a)와 비교하여 데이터셋A는 28.44%, 데이터셋B는 63.45% 향상되었으며, USBL 위치와의 평균오차는 데이터셋 A는 18.92%, 데이터셋 B는 33.05% 향상되었다. 또한 방법(c)의 경우 끝점오차는 방법(a)와 비교하여 데이터셋A는 32.19%, 데이터셋B는 75.49% 향상되었으며, USBL 위치와의 평균오차는 데이터셋 A는 14.86%, 데이터셋B는 29.63% 향상되었다. 특히 관성항법만 사용한 방법(a)를 사용했을 때 [Fig. 15]와 같이 USBL 위치와 비교해 항법 추정위치의 오차가 큰 데이터셋 B의 경우에서 더욱 위치추정 결과가 개선됨을 확인하였다.
Localization result of dataset A using method (a) : (method (a) represents the result of the inertial navigation system)
Localization result of dataset A using method (b): (method (b) represents the result of the proposed method)
Localization result of dataset A using method (c): (method (c) represents the result of the proposed method with the initial alignment time reduced to 10 seconds)
Localization result of dataset B using method (a) : (method (a) represents the result of the inertial navigation system)
Localization result of dataset B using method (b): (method (b) represents the result of the proposed method)
Localization result of dataset B using method (c): (method (c) represents the result of the proposed method with the initial alignment time reduced to 10 seconds)
4. 결 론
본 논문에서는 스쿠버 다이버의 안전한 다이빙활동을 위한 가이드용, 구조용 안전지원 로봇의 정밀한 위치추정을 위해 USBL을 이용하여 운항 중 지속적으로 헤딩 보정을 진행하는 방법에 대해 제안하였다. 기존 칼만필터 기반의 USBL을 이용한 융합항법은 GPS와 비교해 불확실성이 상대적으로 큰 USBL의 개별 위치의 정확도로 인해 USBL 위치가 수신될 때 마다 로봇의 급격한 위치 변화가 발생하는 문제가 존재했다. 다이버의 위치를 파악해 로봇이 다이버와 일정 거리를 유지하며 기동하는 안전지원로봇의 임무상 로봇의 급격한 위치 변화는 이러한 임무를 위한 제어에도 악영향을 미칠 수 있다. 본 논문은 이러한 문제를 해결하기 위해 선행 연구인 위치기반 정렬방법을 응용하여 초기정렬 이후 수중 운항 중에도 USBL과 관성항법 추정위치를 ICP 알고리즘을 이용해 헤딩 보정값을 산출하고 보정하여 항법 알고리즘 추정 위치의 정확도를 향상시키는 방법을 제안하였다. 제안한 알고리즘을 실해역에서 취득한 데이터셋을 이용하여 실험한 결과 제안한 알고리즘을 적용한 위치추정 결과가 기존 관성항법만을 사용한 위치추정 결과보다 향상됨을 확인하였다. 특히 초기 헤딩추정을 위한 초기정렬 시간을 단축하여 초기 추정 헤딩 정확도가 감소한 상황에서도 제안한 알고리즘을 통해 초기정렬 시간을 단축하지 않는 방법의 위치 추정 정확도와 유사한 성능을 보임을 확인하였다. 이를 통해 안전지원로봇이 진수 위치에서 초기정렬을 위해 이동하는 시간을 단축하여 보다 신속한 안전지원 임무를 수행할 수 있을 것으로 기대할 수 있다. 추후에는 기존 수상에서 GPS를 이용하여 진행하는 초기정렬을 수중에서 USBL을 이용해 진행하여 안전지원로봇이 별도의 수상 기동 없이 진수 후 즉각적인 임무를 수행할 수 있도록 연구를 진행하고자 한다.
Acknowledgments
This research was supported by Korea Institute of Marine Science & Technology Promotion (KIMST) funded by the Ministry of Oceans and Fisheries (Grant No. 20220567).
References
-
K.-S. Kang and H.-S. Song, “The Effect of Scuba Diver Education on Emergency Response Ability, Safety Knowledge and First Aid Awareness of University Students,” Journal of the Korea Society of Computer and Information, vol. 28, no. 5, pp. 121-127, May, 2023.
[https://doi.org/10.9708/jksci.2023.28.05.121]
-
H.-C. Park, J.-Y. Hwang, and K.-J. Cho, “A Study on Actual Condition of Diving Safety before Scuba Diving and during Scuba Diving According to Scuba Diver’s Characteristics,” Journal of the Korea Academia-Industrial cooperation Society, vol. 16, no. 2, pp. 1216-1226, Feb., 2015.
[https://doi.org/10.5762/KAIS.2015.16.2.1216]
-
B. Zhang, D. Ji, S. Liu, X. Zhu, and Wen Xu, “Autonomous Underwater Vehicle navigation: A review,” Ocean Engineering, vol. 273, Apr., 2023.
[https://doi.org/10.1016/j.oceaneng.2023.113861]
-
J. Melo and A. Matos, “Survey on advances on terrain based navigation for autonomous underwater vehicles,” Ocean Engineering, vol. 139, pp. 250-264, Jul., 2017.
[https://doi.org/10.1016/j.oceaneng.2017.04.047]
-
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]
-
C. Zheng, Y. Liu, D. Sun, and Y. Zhao, “The Outlier Elimination Methodology of Ultra-Short BaseLine Positioning Data,” 2019 International Conference on Control, Automation and Information Sciences (ICCAIS), Chengdu, China, pp. 1-6, 2019.
[https://doi.org/10.1109/ICCAIS46528.2019.9074558]
-
P. Rigby, O. Pizarro, and S. B. Williams, “Towards Geo-Referenced AUV Navigation Through Fusion of USBL and DVL Measurements,” OCEANS 2006, MA, USA, pp. 1-6, 2006.
[https://doi.org/10.1109/OCEANS.2006.306898]
-
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, 2017.
[https://doi.org/10.26748/KSOE.2017.08.31.4.315]
-
M. Xia, T. Zhang, L. Zhang, B. Yang, and Y. Shi, “A Mixture Distribution-Based Robust SINS/USBL Integration Navigation With Time-Varying Delays,” IEEE Transactions on Instrumentation and Measurement, vol. 73, pp. 1-10, 2024.
[https://doi.org/10.1109/TIM.2024.3381293]
-
G.-H. Kim, J. Lee, P.-Y. Lee, H. S. Kim, and H. Lee, “GPS and inertial sensor-based navigation alignment algorithm for initial state alignment of AUV in real sea,” Journal of Korea Robotics Society, vol. 15, no. 1, pp. 16-23, Feb., 2020.
[https://doi.org/10.7746/jkros.2020.15.1.016]
-
J. Choo, G. Lee, P.-Y. Lee, H. S. Kim, H. Lee, D. Park, and J. Lee, “Position based in-motion alignment method for an AUV,” Journal of Institute of Control, Robotics and Systems, vol. 26, no. 8, pp. 649-659, Aug., 2020.
[https://doi.org/10.5302/J.ICROS.2020.20.0071]
-
G. Lee, K. Choi, P.-Y. Lee, H. S. Kim, H. Lee, H. Kang, and J. Lee, “Performance Enhancement Technique for Position-based Alignment Algorithm in AUV’s Navigation,” Journal of Institute of Control, Robotics and Systems, vol. 29, no. 9, pp. 740-747, Sept., 2023.
[https://doi.org/10.5302/J.ICROS.2023.23.0081]
-
H. Sim and H. Joe, “Voronoi Diagram-based USBL Outlier Rejection for AUV Localization,” Journal of Ocean Engineering and Technology, vol. 38, no. 3, pp. 115-123, 2024.
[https://doi.org/10.26748/KSOE.2024.049]
-
M. Morgado, P. Oliveira, and C. Silvestre, “Robust Outliers Detection and Classification for USBL Underwater Positioning Systems,” CONTROLO’2014 – Proceedings of the 11th Portuguese Conference on Automatic Control, vol. 321, pp. 555-565, 2015.
[https://doi.org/10.1007/978-3-319-10380-8_53]
-
P.-M. Lee, J.-Y. Park, H. Baek, S.-M. Kim, B.-H. Jun, H.-S. Kim, and P.-Y. Lee, “Underwater Navigation of AUVs Using Uncorrelated Measurement Error Model of USBL,” Journal of Ocean Engineering and Technology, vol. 36, no. 5, pp. 340-352, 2022.
[https://doi.org/10.26748/KSOE.2022.019]
-
B. Xu, J. Zhang, and A. A. Razzaqi, “A novel robust filter for outliers and time-varying delay on an SINS/USBL integrated navigation model,” Measurement Science and Technology, vol. 32, no. 1, Oct., 2021.
[https://doi.org/10.1088/1361-6501/abaae9]
-
D. Ribas, P. Ridao, A. Mallios, and N. Palomeras, “Delayed State Information Filter for USBL-Aided AUV Navigation,” IEEE International Conference on Robotics and Automation, Saint Paul, MN, USA, pp. 4898-4903, 2012.
[https://doi.org/10.1109/ICRA.2012.6224989]
2022 충남대학교 메카트로닉스공학과(학사)
2022~현재 충남대학교 메카트로닉스과 석사과정
관심분야: 자율무인잠수정, 수중항법, USBL
2020 충남대학교 메카트로닉스공학과(학사)
2023 충남대학교 메카트로닉스과 석,박통합과정 수료
2023~현재 충남대학교 미래모빌리티시스템연구소
관심분야: 자율무인잠수정, 항법, 수중소나
2022 충남대학교 메카트로닉스공학과(학사)
2022~현재 충남대학교 메카트로닉스과 석,박통합과정
관심분야: 위치추정, 항법, 수중로봇, 수중소나
2001 KAIST 기계공학과(학사)
2003 KAIST 기계공학과(석사)
2010 KAIST 기계공학과(박사)
2010~2016 삼성중공업 책임연구원
2016~현재 한국로봇융합연구원 수석연구원
관심분야: 수중로봇, 강인제어, 매니퓰레이션
2012 동명대학교 로봇시스템공학과(학사)
2014 동명대학교 기계시스템공학과(석사)
2014~현재 한국로봇융합연구원
관심분야: 인공지능, 제어이론, 해양로봇
1983 서울대학교 전자공학과(학사)
1985 KAIST 전기 및 전자공학과(석사)
1991 KAIST 전기 및 전자공학과(박사)
1994~현재 충남대학교 메카트로닉스공학과 교수
관심분야: 위치 추정, 수중 로봇, 양팔 로봇, 야지 주행 로봇

![[Fig. 1] [Fig. 1]](/xml/45118/JKROS_2025_v20n2_337_f001.jpg)
![[Fig. 2] [Fig. 2]](/xml/45118/JKROS_2025_v20n2_337_f002.jpg)
![[Fig. 3] [Fig. 3]](/xml/45118/JKROS_2025_v20n2_337_f003.jpg)
![[Fig. 4] [Fig. 4]](/xml/45118/JKROS_2025_v20n2_337_f004.jpg)
![[Fig. 5] [Fig. 5]](/xml/45118/JKROS_2025_v20n2_337_f005.jpg)
![[Fig. 6] [Fig. 6]](/xml/45118/JKROS_2025_v20n2_337_f006.jpg)
![[Fig. 7] [Fig. 7]](/xml/45118/JKROS_2025_v20n2_337_f007.jpg)
![[Fig. 8] [Fig. 8]](/xml/45118/JKROS_2025_v20n2_337_f008.jpg)
![[Fig. 9] [Fig. 9]](/xml/45118/JKROS_2025_v20n2_337_f009.jpg)
![[Fig. 10] [Fig. 10]](/xml/45118/JKROS_2025_v20n2_337_f010.jpg)
![[Table 1]](../img/npr_tablethum.jpg)