아주 예전에 당시 한 연구원과 함께 DC 모터를 제어하기 위한 다양한 여러 방법들을 확인하고 실험하면서 여러가지 가능성을 확인했던 적이 있는데요. 그 중에 위치 프로파일링에 대해 이야기를 했던 적이 있습니다.[바로가기] 당시 프로파일링을 하면서 여러가지 실무적 어려움이 있었는데요. 그 중에 가장 고민했던 것 하나를 오늘 이야기해 볼까 합니다.
먼저 위 그림을 보죠. 빨간색이 사다리꼴 속도 프로파일이구요. 파란선이 그걸 적분한 위치 프로파일입니다. 사실 그냥 저것만 보면 아주아주 쉬운 것 처럼 보입니다만... 이게 좀 ... 실제로 해보면 약간 어려운 곳이 있습니다. 뭐냐면 바로 감속구간을 설정하는 것이지요.
일단, 0초부터 1초까지의 가속구간은 위 식처럼 그냥 가속도를 이용해서 만들어낼 수 있습니다.
그리고 속도 한계가 정해져 있다면 가속구간에서 구하는 속도기준값이 설정된 속도 한계를 넘어서는 경우에 등속운동을 하도록한 1초부터 3초까지의 구간도 쉽게 만들어 집니다.
그러나 3초 이 후의 감속 구간은 처음 모터 제어를 하는 경우 어려움을 만나게 됩니다. 뭐냐면 언제부터 감속하는가? 하는 문제입니다. 이 때문에 당시[바로가기]에 저는 이를 수학적 함수(atan, 10차 이상의 다항식 등등)으로 위치를 다듬는 실험과 혹은 위치 지령이 충분히 빠른 주기로 인가된다면 그냥 한 샘플 기다렸다가 알게된 두 지령으로 구한다든지 하는 방법들을 테스트 했는데요. 물론 뭐 새로운건 아니고 다 인터넷에 있는 자료들(^^)이지요^^. 그 중에 한가지 - 그러면서도 썩 괜찮은 - 방법을 오늘 다루죠...
일반적으로 알려진 가속도(a)를 가지고 구한 속도와 그걸 적분한 위치의 위 두식에서 시간(t)를 소거하는 방향으로 정리하면
이렇게 되죠... 이게 또 하나의 방법이 됩니다^^. 일단
감속 구간의 속도 기준 신호를 다시 표현하고... 여기서
입니다. 흠.. Sref는 현재의 위치 기준값이구요. Starget은 원래 지정된 위치 목표값입니다. 근호안에 있으니 당연히 절대값이어야죠^^
이제 최종적인 사다리꼴 속도 기준 신호는 위 식과 같습니다.^^.
ts = 0.001; t = 0:ts:5; targetPos = 12; acc = 4; maxVel = 4; posRef = zeros(1, length(t)); velRef = zeros(1, length(t)); tmp = zeros(1, length(t)); for i = 2:length(t) if targetPos > posRef(i-1) velRef(i) = min([(velRef(i-1) + acc*ts), maxVel, sqrt(2*acc*abs(targetPos-posRef(i-1)))]); elseif targetPos < posRef(i-1) velRef(i) = max([(velRef(i-1) - acc*ts), -maxVel, -sqrt(2*acc*abs(targetPos-posRef(i-1)))]); end posRef(i) = posRef(i-1) + velRef(i)*ts; end plot(t, posRef, t, velRef, 'r'); grid on
위 코드는 그걸 구현해본 MATLAB 예제 이구요. 기간을 미리 행렬로 저장해버렸기 때문에 그냥 저렇게 표현해버렸습니다. 아무튼 이 코드의 결과는 제일 처음 그림인
입니다. 실제 목표는 0초 지점에서 한번 지령된 것이구요. 이미 설정된 가속능력과 최대 허용 속도등을 이용해서 사다리꼴 속도 프로파일을 만들고, 그걸 적분해서 위치 프로파일을 만들면 됩니다. 아.. 그냥 시뮬레이션의 편의를 위해서 감속과 가속 능력은 그냥 같다고 가정했습니다.^^.
'Theory > ControlTheory' 카테고리의 다른 글
[DC 모터 제어] 모터의 속도 제어기 설계 및 MATLAB 시뮬레이션 (20) | 2015.05.21 |
---|---|
엑셀에서 저역통과필터 (Low Pass Filter) 구현하기 (48) | 2015.05.12 |
[DC 모터 제어] DC 모터 동역학 및 전류제어기의 MATLAB을 이용한 시뮬레이션 (44) | 2015.04.14 |
MATLAB을 이용하여 Two Link Planar의 역기구학 해석하기 (16) | 2014.12.03 |
정방향 기구학(forward kinematics)의 기초와 Two Link Planar 예제 (22) | 2014.11.14 |
델타형 병렬 로봇의 역기구학을 단순 기하학적으로 손쉽게 해석해보기 (10) | 2014.04.25 |
저역통과필터와 고역통과필터를 C로 구현 (39) | 2011.06.01 |