Journal of Korea Robotics Society
[ ARTICLE ]
The Journal of Korea Robotics Society - Vol. 19, No. 1, pp.8-15
ISSN: 1975-6291 (Print) 2287-3961 (Online)
Print publication date 29 Feb 2024
Received 19 Sep 2023 Revised 09 Nov 2023 Accepted 23 Nov 2023
DOI: https://doi.org/10.7746/jkros.2024.19.1.008

비선형 강인 내부루프 보상기를 이용한 6자유도 원격조종 수중로봇의 선형 모델예측 제어

김준식1 ; 최유나1 ; 이동철2 ; 최영진
Linear Model Predictive Control of 6-DOF Remotely Operated Underwater Vehicle Using Nonlinear Robust Internal-loop Compensator
Junsik Kim1 ; Yuna Choi1 ; Dongchul Lee2 ; Youngjin Choi
1Ph.D. Student, Department of Electrical and Electrical and Electronic Engineering, Hanyang University, Ansan, 15588, Korea scott9569@hanyang.ac.krchldbsk2220@hanyang.ac.kr
2Principal Researcher, Samsung SDS & Ph.D. Candidate, Department of Electrical and Electronic Engineering, Hanyang University, Ansan, 15588, Korea ddamjil@hanyang.ac.kr

Correspondence to: Professor, Corresponding author: Department of Electrical and Electronic Engineering, Hanyang University, Ansan, 15588, Korea ( cyj@hanyang.ac.kr)

CopyrightⓒKROS

Abstract

This paper proposes a linear model predictive control of 6-DOF remotely operated underwater vehicles using nonlinear robust internal-loop compensator (NRIC). First, we design a integrator embedded linear model prediction controller for a linear nominal model, and then let the real model follow the values calculated through forward dynamics. This work is carried out through an NRIC and in this process, modeling errors and external disturbance are compensated. This concept is similar to disturbance observer-based control, but it has the difference that Hoptimality is guaranteed. Finally, tracking results at trajectory containing the velocity discontinuity point and the position tracking performance in the disturbance environment is confirmed through the comparative study with a traditional inverse dynamics PD controller.

Keywords:

Remotely Operated Underwater Vehicle (ROV), Model Predictive Control (MPC)

1. 서 론

원격조종 수중로봇(Remotely operated vehicle, ROV)은 수중환경에서 탐사, 수집 등의 다양한 작업을 수행 함에 있어 최근 그 활용도가 높아지고 있다. 이때 원격조종 수중로봇이 작업을 성공적으로 수행하기 위해서는 스스로 자세의 안정성을 유지하며 주어진 목표 궤적을 추종해야 한다. 따라서 동작 신뢰성과 작업 정확도를 위한 다양한 제어 기법들[1-3]이 연구되었다. 하지만 이러한 제어 알고리즘들은 해류, 난류 등의 외란으로 인해 시스템의 비선형성이 커짐에 따라 성능이 저하되는 단점이 있으며, 미래 거동의 궤적을 고려하지 않아 부드럽지 않은 궤적에 대해 불안정한 모습을 보인다. 이에 대한 해결책인 모델예측 제어(Model Predictive Control, MPC)[4-6]는 미래 거동의 궤적을 예측하여 최적 제어 문제를 해결하는 모델 기반의 제어 알고리즘이다. 하지만 지상환경과는 달리 수중환경에서는 유체의 특성으로 인해 부가 질량계수(added mass coefficient), 부가 코리올리계수(added Coriolis coefficient), 감쇠계수(damping coefficient)에 대한 정보가 추가로 요구되며 이를 얻기 위한 계산 과정[7]이 복잡하고 환경에 따른 불확실성이 크기 때문에, 모델에 대한 정확도가 보장되지 않는다는 문제가 있다. 또한 비선형 모델예측 제어 알고리즘의 경우 연산량이 많아진다는 단점이 생긴다.

따라서 본 논문에서는 비선형 강인 내부루프 보상기(Nonlinear Robust Internal-loop Compensator, NRIC)[8]를 이용한 6자유도 원격조종 수중로봇의 선형 모델예측 제어(Linear Model Predictive Control, LMPC)기법을 제안한다. 먼저 선형 공칭 모델에 대한 선형 모델예측 제어기를 설계한 뒤, 순동역학(forward dynamics)을 통해 계산된 값을 실제 모델이 추종하도록 한다. 이 작업은 비선형 강인 내부루프 보상기를 통해 진행되며, 이 과정에서 모델링 오차와 외부의 외란(external disturbance)이 보상된다. 이 개념은 외란 관측기(Distrubacne Observer, DOB) 기반 제어[9]와 유사하지만 H최적성이 보장된다는 차이점을 갖는다.

본 논문의 주요 내용 및 구성은 다음과 같다. 2장에서 원격조종 수중로봇의 기구학/동역학 모델링을 진행한다. 3장에서는 비선형 강인 내부루프 보상기 및 선형 모델예측 제어기의 구성 방법을 논하고, 4장에서는 시뮬레이션을 통해 제안된 제어 방법과 기존의 기법을 비교하여 검증한다. 마지막으로 5장에서 결론을 통해 논문을 마무리 짓는다.


2. 원격조종 수중로봇(ROV) 모델링

2.1 기준 좌표계

본 논문에서는 [Fig. 1]에 제시된 차체 고정 좌표계와 지구 고정 좌표계, 두 가지 기준 좌표계를 사용하여 원격조종 수중로봇의 모델링을 진행한다. 지구 고정 좌표계에 대한 원격조종 수중로봇의 위치벡터는 η = [x,y,z,ϕ,θ,ψ]T로 표현하며, (x,y,z)와 (ϕ,θ,ψ)는 각각 위치와 각도를 나타낸다. 차체 고정 좌표계에 대한 속도는 벡터 ν = [u,v,w,p,q,r]T로 나타낼 수 있고, (u,v,w)와 (p,q,r)는 각각 선속도와 각속도를 의미한다.

[Fig. 1]

Body-fixed and Earth-fixed reference frames

2.2 기구학 모델

원격조종 수중로봇의 속도 기구학과 가속도 기구학은 다음 식 (1)과 같이 나타난다.

η˙=Jην,η¨=Jην˙+J˙ην(1) 

여기서, J(η)∈R6×6 는 차체 고정 좌표계에서의 속도 ν와 지구 고정 좌표계 속도 η˙사이의 자코비안 행렬이며 아래의 식 (2)와 같다.

Jη=J1η03×303×3J2η(2) 

이때, J1(η)∈R3×3는 선속도 변환 행렬이며 식 (3)과 같고, J2(η)∈R3×3는 각속도 변환 행렬로 식 (4)와 같다.

J1η=cψcθ-sψcϕ+cψsθsϕsψsϕ+cψcϕsθsψcθcψcϕ+sψsθsϕ-cψsϕ+sψsθcϕ-sθcθsϕcθcϕ(3) 
J2η=1sψsθ/cθcϕsθ/cθ0cϕ-sϕ0sϕ/cθcϕ/cθ(4) 

식 (3)-(4)로부터 자코비안 행렬의 모든 원소가 sin과 cos으로만 이루어져 있다는 사실을 확인할 수 있으며, 이를 통해 자코비안 행렬의 미분 J'ηR6×6또한 간단하게 유도할 수 있음을 알 수 있다.

2.3 동역학 모델

차체 고정 좌표계에서 기술된 원격조종 수중로봇의 동역학 모델은 식 (5)와 같으며, 각 항의 의미는 아래의 설명을 따른다.

Mν˙+Cνν+Dνν+gη=τ+d(5) 
  • · MR6×6 : 상수로만 구성되는 관성 행렬.
  • · C(ν)∈R6×6 : 속도의 함수로 기술되는 코리올리 행렬.
  • · D(ν)∈R6×6 : 수중환경으로 인한 감쇠 행렬.
  • · g(η)∈R6 : 위치의 함수로 기술되는 중력과 부력 벡터.
  • · τR6×1 : 힘과 모멘트 벡터.
  • · dR6×1 : 외부 외란 벡터.

여기서 MC(ν)에는 각각 수중환경으로부터의 부가 관성 행렬(added inertia matrix) MaR6×6와 부가 코리올리 행렬(added Coriolis matrix) Ca(ν)∈R6×6가 포함되어 있다. 따라서 M=Mrb+Mb, C(ν) = C(ν)rb+C(ν)a와 같이 나타낼 수 있다. 이때 Mrb, Crb(ν)는 각각 원격조종 수중로봇 강체의 관성 행렬과 코리올리 행렬이다.


3. 제안 방법

본 논문에서 제안된 방법은 다음과 같이 요약된다. 비선형 시스템인 실제 모델 대신 선형 시스템인 공칭 모델에 대한 모델 예측 제어기를 설계한 뒤, 외부의 외란, 모델링 오차를 포함한 공칭 성능과 실제 성능 사이의 편차를 비선형 강인 내부루프 보상기를 이용하여 보상한다. [Fig. 2]는 제안된 제어기의 블록선도를 나타낸다. 아래첨자 (⋅)R, (⋅)N은 각각 실제, 공칭 모델과 관련된 신호임을 뜻하며. ^은 (⋅)의 추정값을 의미한다.

[Fig. 2]

Block diagram of the linear model predictive controller using nonlinear robust internal-loop compensator

3.1 비선형 강인 내부루프 보상기(NRIC)

이번 절에서는 먼저 비선형 강인 내부루프 보상기를 구성한다. 핵심 개념은 공칭 성능에 영향을 주지 않고 실제 성능과의 편차를 감쇠시키는 보조 입력을 설계하는 것이다. 이를 통해 기존의 제어입력에 단순히 보조 입력을 추가함으로써 강인함을 부여할 수 있게 된다.

실제 원격조종 수중로봇의 폐루프 동역학([Fig. 2]의 파선 영역)과 공칭 모델의 폐루프 동역학([Fig. 2]의 점선 영역)은 각각 다음의 식 (6)-(7)과 같이 표현된다.

τ=MRνR˙+CνR+DνRνR+gηR(6) 
τc=MNν˙N(7) 

이때 MR=M, MN=M^rb이다. 위의 식 (6)-(7)의 차를 τ=τc+τnl+τa+d의 관계를 이용하여 식 (8)로 정리가 가능하다.

τa+w=MReRN¨+Kpe˙RN+CνRe˙RN+KpeRN(8) 

eRN, e˙RN, e¨RN는 각각 νR-νNdt, νR-νN, ddtνR-νN이며, 실제 모델과 공칭 모델 사이의 추종 오차이다. w는 확장 외란(extended disturbance)으로 식 (9)와 같다.

w=MN-MRν˙N+C^νRνR-CνRνN-DνRνR+g^ηR-gηR+d+MRKpe˙RN+CνRKpeRN(9) 

이어서 식 (8)을 정리하여 아래의 식 (10)과 같은 상태공간 방정식(state-space equation)을 얻을 수 있다.

x˙RN=AxRN+Bw+Bτa(10) 

이때 xRN=eRN e˙RNT, x˙RN=e˙RN e¨RNT이며, A,B는 각각 식 (11)-(12)와 같다.

A=06×6I6×6-MR-1CνRKp-MR-1CνR-Kp(11) 
B=06×6MR-1(12) 

최종적으로 식 (10)을 통해 식 (13)L2이득 감쇠 요건을 충족시키는 비례-미분(Proportional-Derivative, PD) 형태의 보조 입력 τa식 (14)와 같이 얻을 수 있다.

0TxRNTQxRN+τaTRτadtγ20TwTwdt(13) 
τa=-K+1γ2I6×6e˙RN+KpeRN(14) 

여기서 γRL2이득, QR12×12RR12×12은 가중 행렬이며, KR6×6KpR6×6는 대각 이득 행렬이다. 구체적인 유도과정과 안정도에 대한 증명은 기존의 연구 결과[8]로 대체한다.

3.2 선형 모델예측 제어(LMPC)

이번 절에서는 공칭 모델에 인가될 제어입력을 생성하는 적분기가 내장된(embedded integrator) 상태공간 모델의 이산시간 예측 제어기를 구성한다. 앞선 식 (7)은 차체 고정 좌표계에서 기술한 공칭 모델의 동역학이다. 이를 에너지 보존 법칙으로부터 유도된 τc=JNTFc의 관계를 이용하여, 지구 고정 좌표계에서 다시 기술하면 식 (15)와 같이 표현할 수 있다.

Fc=J-TNMNJ-1Nη¨N-J-TNMNJ-1NJ˙NJ-1Nη˙N(15) 

여기서 JNR6×6, J˙NR6×6는 각각 공칭 모델의 자코비안 행렬과 그것의 시간 미분이다. 위의 식 (15)를 다시 정리하여 식 (16)의 선형 상태공간 방정식을 유도할 수 있고, 이를 이산화하여 식 (17)이 얻어진다.

x˙ηN=ANxηN+BNFc, yηN=CNxηN(16) 
xdk+1=Adxdk+Bduk,  yk=Cdxdk(17) 

이때 xηN=ηN η˙NT, x˙ηN=η˙N η¨NT, CN=I12×12이고, AN,BN식 (18)과 같으며, Ad,Bd,Cd는 각각 AN,BN,CN을 이산화하여 얻어진 행렬이다. 여기서 MN-1는 상수로 구성되어 있으며, 앞서 언급했듯 JN-1, J˙N 모두 사전에 형태를 구성이 가능한 함수이기 때문에 AN, BN을 계산하기 위한 연산시간을 단축할 수 있다.

AN=06×6I6×606×6J˙NMN-1,BN=06×6JNTMN-1JN(18) 

적분기를 내장하기 위해 식 (17)을 차분하여 정리하면 식 (19)가 유도된다.

Δxmk+1=AdΔxmk+BdΔuk      yk+1=CdAdΔxmk+CdBdΔuk(19) 

여기서Δxm(k+1)은 xm(k+1) - xm(k), Δxm(k)은 xm(k)-xm(k-1)을 뜻한다. 다시 식 (19)를 통해 식 (20)의 확장된(augmented) 상태공간 모델을 얻을 수 있다.

Δxmk+1yk+1=Ad06×6CdAdI6×6Δxmkyk+BdCdBdΔukxk+1=Aaxk+BaΔuk,yk=06×6I6×6Δxmkykyk=Caxk(20) 

식 (20)으로부터 예측 상태변수와 예측 출력변수 사이의 관계는 식 (21)로 정리된다.

Y=Fxk+ΦΔU(21) 

이때 YR6Np는 예측 출력변수의 궤적 벡터, ΔUR6Nc는 예측 제어입력의 궤적 벡터이며 Np(prediction horizon)과 Nc(control horizon)은 각각 예측하고 싶은 미래의 상태와 제어입력의 개수를 뜻한다. 또한 FΦ는 각각 R6Np×6, R6Np×6Nc차원을 갖는 행렬이다. 이제 식 (22)의 목적함수를 최소화하는 ΔU식 (23)과 같이 유도할 수 있다.

J=12Rs-YTRs-Y+12ΔUTRwΔU(22) 
ΔU=ΦTΦ+Rw-1ΦTRs-Fxk(23) 

여기서 RsR6Np는 지구 고정 좌표계 기준 미래의 목표 궤적이고 RwR6Nc×6Nc는 제어입력에 대한 가중 행렬이다. 최종적으로 선형 모델예측 제어기로부터의 출력 Fc식 (24)Δu(k)를 누적하여 구할 수 있다. 앞선 장에서와 같이 구체적인 유도과정은 기존의 연구 결과[10]로 대체하도록 한다.

Δuk=I6×606×606×6ΔU(24) 

4. 시뮬레이션 및 결과

제안된 방법의 검증을 위해 시뮬레이션을 진행한 뒤, 그 결과를 분석한다. 모든 시뮬레이션은 Blue Robotics社의 BlueROV2모델[11] 정보를 이용하여 MATLAB 2023a 버전에서 진행되었고, 제어입력에 대한 제한과 추력기(thruster)에 대한 모델링은 따로 고려하지 않았다. 또한 공칭 모델과 실제 모델에 대한 순동역학 적분은 각각 오일러 방법(Euler method)과 4차 룽게-쿠타 방법(RK4 method)을 사용하여 진행되었다. 제안된 제어기에서 사용한 파라미터의 값은 식 (25)와 같다.

Np=50, Nc=5, Rw=5e-3I30×30,K=50I6×6, 1γ2=5, Kp=100I6×6(25) 

4.1 궤적 추종 결과

[Fig. 3]은 [Table 1]에 주어진 속도에 대해 불연속적인 구간이 포함된 목표 궤적을 역동역학 비례-미분 제어기(inverse dynamics PD controller)[1]와 제안된 제어기가 추종한 결과를 비교하여 나타낸다. 시뮬레이션은 40초 동안 100[Hz]의 제어 주기로 진행되었고, 이때 역동역학 비례-미분 제어기는 원격조종 수중로봇의 모델 파라미터 정보를 모두 알고 있다고 가정하여 제어기를 구성하였으며, 비례 이득과 미분 이득 값은 각각 50diag (1,1,1,1,1,1), 30diag (1,1,1,1,1,1)을 사용하였다. 여기서 이득 값은 여러 번의 시뮬레이션을 통하여, 목표 궤적을 잘 추종하되 제어입력을 너무 크게 하지 않는 적절한 값을 선정하였다. 반면 제안된 제어기는 Ma, Ca(ν), D(ν)에 대한 정보를 사용하지 않고 구성하였다. [Fig. 3(b)], [Fig. 3(c)], [Fig. 3(d)]은 각각 [Fig. 3(a)]의 첫 번째(8[s]), 두 번째(16[s]), 세 번째(24[s]) 속도 불연속 구간에서의 결과를 확대한 그래프이다. 각 그래프에서 확인할 수 있듯, 역동역학 비례-미분 제어기와 달리 제안된 제어기는 속도 불연속 구간에 도달하기 전에 미리 대응하는 모습을 볼 수 있다. [Fig. 4]는 시뮬레이션을 진행한 40초 동안의 제어입력 궤적을 비교한 그래프이다. 전체적으로 제안된 제어기에서 생성된 입력값이 작은 것을 확인할 수 있으며, 특히 속도 불연속 지점(8[s], 16[s], 24[s], 32[s])에서의 각 제어기의 제어 입력값을 비교해 보면 약 10배 정도의 차이를 보인다. 이를 통해 속도 불연속 궤적에 대한 제안된 방법의 이점을 확인할 수 있다.

[Fig. 3]

Comparisons of the tracking results at trajectory containing the velocity discontinuity point between proposed controller and inverse dynamics PD controller

Desired trajectory

[Fig. 4]

Comparisons of the control input trajectory of the between proposed controller and inverse dynamics PD controller

4.2 모델 불확실성, 외란에 대한 제어기 성능 비교

[Fig. 3]에서 볼 수 있듯, 제안된 제어기는 주어진 궤적을 그대로 추종하는 것이 아닌, 속도 불연속 구간에 대해 미리 대응하는 모습을 보인다. 그러므로 목표 궤적이 속도 불연속 구간을 포함하는 경우, 제어기 사이의 궤적 추종 성능에 대한 직접적인 비교가 어렵다. 따라서 이번 절에서는 목표 궤적이 속도 불연속 구간을 포함하지 않는, 전 구간에서 목표 궤적의 값이 모두 0인 회전 성분에 대한 비교를 진행한다. [Fig. 5]는 4.1절과 같은 조건에서 정현파 형태의 외부 외란 d= 10sin (2πt) diag (1,1,1,0.1,0.1,0.1)[N or Nm]을 추가하였을 때 ϕ,θ,ψ값을 비교한 그래프이다. [Fig. 5(a)], [Fig. 5(b)]의 비교를 통해 완전한 모델 정보를 이용하여 구성한 기존의 역동역학 비례-미분 제어기보다 본 논문에서 제안한 제어기가 외란이 존재하는 환경에서의 위치 추종 성능이 더욱 뛰어나다는 것을 확인할 수 있으며, 추종 궤적과의 RMSE (root mean squared error) [0.0124, 0.0154, 0.0136](역동역학 비례-미분제어기), [2.2500e-04, 4.3752e-04, 0.0124](제안된 제어기)를 비교하여 수치적 검증 또한 가능하다. [Fig. 5(b)], [Fig. 5(c)]는 비선형 강인 내부루프 보상기를 통해 실제 모델이 공칭 모델을 추종한 결과를 보여준다. 모델 불확실성과 외란이 있는 환경에도 불구하고 실제 ϕ,θ,ψ가 [1.3085e-04, 1.2678e-04, 2.4032e-04]의 RMSE값을 보이며 공칭 ϕ,θ,ψ를 추종하는 모습을 확인 할 수 있다. [Fig. 5(b)]에서 ψ의 경우 ϕ,θ와 비교했을 때 공칭값이 1e-06단위로 아주 작은 값이기 때문에, 실제 ψ가 공칭 ψ의 경향성을 완전히 따라가지 못하는 모습을 보인다. 하지만 실제 ψ 값은 1e-03단위로 다른 회전 성분들과 크기가 비슷하며, 여전히 기존의 역동역학 비례-미분 제어기의 결과보다 작은 값을 가짐을 알 수 있다.

[Fig. 5]

Position tracking performances of the inverse dynamics PD controller (a), proposed controller (b) and nominal controller (c), Note that the scale of ψ in [Fig. 5(b)] and [Fig. 5(c)] is 1e-04 and 1e-06, respectively


5. 결 론

본 논문에서는 비선형 강인 내부루프 보상기를 이용한 6자유도 원격조종 수중로봇의 선형 모델예측 제어 기법을 제안하였다. 먼저 공칭 모델에 대한 선형 모델예측 제어기를 설계하였으며, 순동역학을 통해 계산된 값을 비선형 강인 내부루프 보상기를 통해 실제 모델이 추종하게 하였고, 이 과정에서 모델의 불확실성으로 인해 생기는 외란과 외부 외란을 함께 보상하였다. 마지막으로 시뮬레이션을 통해 제안된 제어기의 성능을 기존 제어기와의 비교 실험을 통해 검증하였다.

Acknowledgments

This work was supported in part by the Institute of Civil Military Technology Cooperation funded by the Defense Acquisition Program Administration and Ministry of Trade, Industry and Energy of Korean government under grant No. UM22318RD3, Republic of Korea

References

  • T. I. Fossen, 2021, Apr., 8, Handbook of Marine Craft Hydrodynamics and Motion Control, (1). [https://doi.org/10.1002/9781119994138]
  • W. M. Bessa, M. S. Dutra, and E. Kreuzer, “Depth control of remotely operated underwater vehicles using an adaptive fuzzy sliding mode controller,” Robotics and Autonomous Systems, vol. 56, no. 8, pp. 670-677, Aug., 2008. [https://doi.org/10.1016/j.robot.2007.11.004]
  • L. Qiao and W. Zhang, “Adaptive non-singular integral terminal sliding mode tracking control for autonomous underwater vehicles,” IET Control Theory Applications for Complex Systems, vol. 11, no. 8, pp. 1293-1306, Mar., 2017. [https://doi.org/10.1049/iet-cta.2017.0016]
  • E. Camacho and C. Bordons, Model Predictive Control, 1999, 1st ed. Springer London, 1999. [https://doi.org/10.1007/978-1-4471-3398-8]
  • A. Molero, R. Duina, J. Cappelletto, and G. Fernandez, “Model Predictive Control of Remotely Operated Underwater Vehicles,” 2011 50th IEEE Conference on Decision and Control and European Control Conference, Orlando, FL, USA, 2011, pp. 2058-2063. [https://doi.org/10.1109/CDC.2011.6161447]
  • Y. Cao, B. Li, Q. Li, A. A. Stokes, D. M. Ingram, and A. Kiprakis, “A Nonlinear Predictive Controller for Remotely Operated Underwater Vehicles with Disturbance Rejection,” IEEE Access, vol. 8, pp. 158622-158634, Aug., 2020. [https://doi.org/10.1109/ACCESS.2020.3020530]
  • Y.-H. Eng, C.-S. Chin, and M. W.-S. Lau, “Added mass computation for control of an open-frame remotely-operated vehicle: Application using WAMIT and MATLAB,” Journal of Marine Science and Technology, vol. 22, no. 4, pp. 405-416, 2014. [https://doi.org/10.6119/JMST-013-0313-2]
  • M. J. Kim, Y. Choi, and W. Chung, “Bringing Nonlinear H∞Optimality to Robot Controllers,” IEEE Transactions on Robotics, vol. 31, no. 3, pp. 682-698, Jun., 2015. [https://doi.org/10.1109/TRO.2015.2419871]
  • J. Kim, D. Lee, and Y. Choi, “Disturbance Observer-Based Control for 6-DOF Remotely Operated Underwater Vehicle with Model Uncertainties,” Journal of Korea Robotics Society, vol. 18, no. 1, pp. 82-87, 2023. [https://doi.org/10.7746/jkros.2023.18.1.082]
  • L. Wang, 2009, Model Predictive Control System Design and Implementation Using MATLAB, 1sted. Springer London, 2009. [https://doi.org/10.1007/978-1-84882-331-0]
  • Y. Xu, “Modeling of a Remotely Operated Vehicle and Tunning for Its Roust and Optimal Dynamic Positioning Control,” M.S. dissertation, University of Stavanger, Stavanger, Norway, 2021, [Online], https://uis.brage.unit.no/uis-xmlui/handle/11250/2786261, .
김 준 식

2020 한양대학교 ERICA 로봇공학과(공학사)

현재 한양대학교 전자공학과(석박사 통합과정)

관심분야: 로봇제어, 시스템 식별

최 유 나

2019 순천향대학교 전자정보공학과(공학사)

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

현재 한양대학교 전자공학과(박사과정)

관심분야: 생체신호처리, 로봇제어

이 동 철

2009 한양대학교 ERICA 전자정보시스템공학과(공학사)

2011 한양대학교 전자전기제어계측공학과(공학석사)

현재 한양대학교 전자공학과(박사과정)

현재 삼성 SDS 책임연구원

관심분야: 로봇 제어, 수중로봇, 군집로봇

최 영 진

2002 POSTECH 기계공학과(공학박사)

2005 KIST 지능로봇연구센터 선임연구원

현재 한양대학교 ERICA 전자공학부 교수

관심분야: 로봇제어, 생체신호처리

[Fig. 1]

[Fig. 1]
Body-fixed and Earth-fixed reference frames

[Fig. 2]

[Fig. 2]
Block diagram of the linear model predictive controller using nonlinear robust internal-loop compensator

[Fig. 3]

[Fig. 3]
Comparisons of the tracking results at trajectory containing the velocity discontinuity point between proposed controller and inverse dynamics PD controller

[Fig. 4]

[Fig. 4]
Comparisons of the control input trajectory of the between proposed controller and inverse dynamics PD controller

[Fig. 5]

[Fig. 5]
Position tracking performances of the inverse dynamics PD controller (a), proposed controller (b) and nominal controller (c), Note that the scale of ψ in [Fig. 5(b)] and [Fig. 5(c)] is 1e-04 and 1e-06, respectively

[Table 1]

Desired trajectory

time(s) ηdes(m,rad) ηdes˙m/s,rad/s
0 ≤ t < 8 12t,0,0,0,0,0T 12,0,0,0,0,0T
8 ≤ t < 16 4,t,0,0,0,0T 0,1,0,0,0,0T
16 ≤ t < 24 12-12t,16-12t,0,0,0,0T -12,-12,0,0,0,0T
24 ≤ t < 32 12-12t,4,0,0,0,0T -12,0,0,0,0,0T
32 ≤ t < 40 12t-20,20-12t,0,0,0,0T 12,-12,0,0,0,0T