저는 RC 컨트롤러를 최소 6채널 이상 되는 녀석으로 바꿀 예정입니다.
지금 사용중인 건(gun)형태의 컨트롤러는 딱 테스트용이라서 테스트 이후 놓아줄 예정입니다...
따라서 위 그림과 같은 전형적인 패드(pad)형 RC 컨트롤러를 예로 생각해 봤습니다.
정리를 해보자
조종 신호 수신
머리로는 대~충 이해가 가지만 막상 코드로 표현하려고 하니 순서가 뒤죽박죽 되더라구요.
먼저 제가 가공할 신호부터 정리 해봤습니다.
기본적으로 Rudder와 Throttle, 이렇게 두 가지 조작이 이루어집니다.
각각의 조작 스틱은 1개의 채널에 할당되어 무선으로 리시버에 전달되며 그 전달된 값의 최대, 최소, 중간값은 이전의 포스팅에서 이미 관찰했었죠.
2021/02/13 - [로봇] - [아두이노] Differential Wheeled RC카 만들기 #1-3 "신호 스케일링"
이 값은 각각 스케일링되어 -100 ~ 100%의 값으로 나타낼 것입니다.
믹서측 신호 가공
자세히가 아닌 대략 이런 식으로 생각하면 되겠다~ 싶을 정도로만 정리를 해봅니다.
입력측에 5%의 데드존을 주어 위와 같이 표현해 봤습니다.
그리고 조작 스틱이 위와 같이 각 위치에 놓여있을 때, 왼쪽과 오른쪽 모터가 얼만큼 회전해야 하는지를 생각해 봤습니다.
위의 두 가지 그림을 보고 생각했을 때 각각의 모터가 얼만큼 회전해야 하는지는 아래와 같이 나타낼 수 있겠네요.
- Left motor = Throttle + Rudder
- Right motor = Throttle - Rudder
이 내용들을 기본으로 코드를 작성했습니다.
코드
#define recvCH1 9 // PWM signal from receiver CH1: Rudder
#define recvCH2 10 // PWM signal from receiver CH2: Throttle
#define motorLeft_EN 3 // Left Motor: ENA(PWM) pin
#define motorLeft_OUT1 2 // Left Motor: IN1 pin
#define motorLeft_OUT2 4 // Left Motor: IN2 pin
#define motorRight_EN 5 // Right Motor: ENB(PWM) pin
#define motorRight_OUT1 7 // Right Motor: IN3 pin
#define motorRight_OUT2 6 // Right Motor: IN4 pin
unsigned long valueCH1; // throttle
unsigned long valueCH2; // rudder
float mixerOut_Left = 0;
float mixerOut_Right = 0;
int getAvg(int channel, int count) {
int sum = 0;
int cnt = 0;
while(cnt < count) {
sum = sum + pulseIn(channel, HIGH, 50000);
cnt++;
}
int avg = sum / count;
return avg;
}
float getScale
(int in_val, float in_min, float in_max, float out_min, float out_max) {
float result = ((out_max-out_min)/(in_max-in_min)) * (in_val-in_max) + out_max;
return result;
}
void mixer(float in_rud, float in_thr) {
int x; // for rudder
int y; // for throttle
Serial.print("\tRud: "); Serial.print(in_rud); Serial.print("%");
Serial. print("\tThr: "); Serial.print(in_thr); Serial.print("%");
// define deadzone for 5%
if((in_thr > (-5)) && ((in_thr) < 5))
y = 0;
else
y = in_thr;
if((in_rud > (-5)) && ((in_rud) < 5))
x = 0;
else
x = in_rud;
mixerOut_Left = y + x;
mixerOut_Right = y - x;
}
void setup() {
Serial.begin(115200);
pinMode(recvCH1, INPUT);
pinMode(recvCH2, INPUT);
pinMode(motorLeft_EN, OUTPUT);
pinMode(motorLeft_OUT1, OUTPUT);
pinMode(motorLeft_OUT2, OUTPUT);
pinMode(motorRight_EN, OUTPUT);
pinMode(motorRight_OUT1, OUTPUT);
pinMode(motorRight_OUT2, OUTPUT);
}
void loop() {
// read RC control signals.
valueCH1 = getAvg(recvCH1, 10); // rudder
valueCH2 = getAvg(recvCH2, 10); // throttle
Serial.print("Rud: "); Serial.print(valueCH1);
Serial. print("\tThr: "); Serial.print(valueCH2);
// call mixer and put scaled values.
mixer(
getScale(valueCH1, 992, 1981, -100.0, 100.0),
getScale(valueCH2, 985, 1967, 100.0, -100.0)
);
Serial.print("\tLeft: "); Serial.print(mixerOut_Left);
Serial.print("\tRight: "); Serial.println(mixerOut_Right);
}
제가 중간 중간 값의 변환이 잘 이루어졌는지 확인하고자 Serial.print()
를 추가했습니다.
loop()
문을 기준으로 설명 드리겠습니다.
// read RC control signals.
valueCH1 = getAvg(recvCH1, 10); // rudder
valueCH2 = getAvg(recvCH2, 10); // throttle
Serial.print("Rud: "); Serial.print(valueCH1);
Serial. print("\tThr: "); Serial.print(valueCH2);
먼저 RC 수신기의 신호를 받아 10회 평균을 적용하여 전역 변수인 valueCH1
과 valueCH2
에 값을 써줍니다.
이 전역 변수는 loop()
문이 시작될 때 마다 계속하여 값이 업데이트 될것입니다.
확인용으로 평균 필터가 적용된 값을 시리얼 모니터에 출력합니다.
이 필터링된 값을 스케일링하여 mixer()
에 인자(argument)로 던져줍니다.
(스케일링 부분은 이미 다룬 내용이기에 건너 뛰겠습니다)
void mixer(float in_rud, float in_thr) {
int x; // for rudder
int y; // for throttle
Serial.print("\tRud: "); Serial.print(in_rud); Serial.print("%");
Serial. print("\tThr: "); Serial.print(in_thr); Serial.print("%");
// define deadzone for 5%
if((in_thr > (-5)) && ((in_thr) < 5))
y = 0;
else
y = in_thr;
if((in_rud > (-5)) && ((in_rud) < 5))
x = 0;
else
x = in_rud;
mixerOut_Left = y + x;
mixerOut_Right = y - x;
}
mixer()
함수 내부는 매우 단순합니다.
백분율로 스케일링된 rudder와 throttle 값을 파라미터로 선언했습니다.
그리고 각각 rudder와 throttle 값을 의미하는 지역 변수 x
와 y
도 선언합니다.
맨 처음 인자가 들어오자 마자 스케일링된 값을 모니터링 하기 위해 시리얼 모니터로 한 번 출력했습니다.
그 후 0%를 기준으로 ±5%의 데드존을 설정했습니다.
(여기서 말하는 데드존은 RC 송신기측에서 발생하는 offset을 잡기 위한 데드존입니다)
입력된 인자값이 데드존 안쪽 범위에 있다면, 해당 값은 0으로 설정됩니다.
데드존 바깥의 값이라면 입력된 값 그대로를 x
와 y
에 저장 및 계산하여 전역 변수 mixerOut_Left
와 mixerOut_Right
를 업데이트 합니다.
// call mixer and put scaled values.
mixer(
getScale(valueCH1, 992, 1981, -100.0, 100.0),
getScale(valueCH2, 985, 1967, 100.0, -100.0)
);
Serial.print("\tLeft: "); Serial.print(mixerOut_Left);
Serial.print("\tRight: "); Serial.println(mixerOut_Right);
스케일된 값을 따로 저장할 변수를 만들까 하다가 귀찮아서 그냥 mixer()
를 호출할 때 한꺼번에 호출했습니다.
결과(모니터링)
rudder를 우측으로 반(+50%), throttle을 전진으로 반(+50%)를 주었을 때 결과입니다.
우측 모터는 회전하지 않고 좌측 모터만 약 100만큼 회전하는 것을 볼 수 있습니다.
개선점
mixer()
를 제작하는 도중에도 "어..? 이렇게 간단하게 되는건가?"라는 생각을 했습니다.
하지만 테스트를 해보면서 몇 가지 의문점이 들기 시작했습니다.
회전비
'회전비'라는 용어가 맞는지는 잘 모르겠지만, 저는 일단 이렇게 부르도록 하겠습니다.
여기서 말하는 '회전'은 모터의 회전(rotation)이 아닌 차체의 회전(steering) 입니다.
시리얼 모니터 결과에서도 볼 수 있듯이, 사용자가 엑셀레이터를 50%, 핸들을 우측으로 50%를 틀었을 때를 예로 삼아보겠습니다.
모니터링 대로라면 좌측 모터가 100만큼, 우측 모터는 0만큼 회전하며 위 그림과 같이 우측 바퀴를 중심 축으로 원을 그리며 이동할 것입니다.
그렇다면 다시, 과연 "일반적으로 사용자가 엑셀레이터를 50%, 핸들을 우측으로 50%를 틀었을 때", 위와 같은 움직임을 예상하고 RC 조종기를 조작했을까요?
먼저, 저만 해도 당연히 위 그림과 같이 움직일 거라고 예상했기 때문이죠.
이러한 결과를 보고나서 문득 일반 자동차가 생각났습니다.
핸들에 따라 전륜이 돌아갈 수 있는 범위가 정해져있기 때문에 핸들을 끝까지 돌려도 회전할 수 있는 정도가 정해져 있습니다.
하지만 양쪽 바퀴 회전수의 차로 구동하는 differential dirve 방법에선 제자리에서 회전하는 것이 가능합니다.
이 두 가지 구동 방식의 중간 타협점을 찾아야 할 것 같습니다.
Full Throttle? & Full Rudder?
말로 설명하기 굉장히 힘든 점인데요...
mixer()
함수의 계산에 따르면, 사용자가 최고 속도로 전진하고자 throttle 값을 최대로 주었을 때 mixerOut_Left
와 mixerOut_Right
값은 아래와 같이 각각 100, 100입니다.
이 상태에서 rudder 값을 좌측으로 천천히 증가시켜 최대로 꺾으면 아래와 같이 좌측 모터는 0, 우측 모터는 200만큼 회전하라는 값이 계산됩니다.
조금 이상하죠?
"엑셀을 full로 밟았을 때 양쪽 바퀴가 둘 다 100만큼 회전했는데, 이 상태에서 좌측으로 핸들을 꺾으니까 왼쪽 모터는 멈추고 오른쪽 모터는 200만큼 회전하네?"
"어? full 엑셀 상태에서보다 Steering이 추가됐을 때 더 빨리 도는건가?"
라는 생각을 했습니다.
이는 위에서 고려해본 회전비와 어느정도 관계가 있지만, 좀 별개의 문제라고 생각됩니다.
다음 포스팅에서는 이 mixer()
가 적용된 값을 기준으로 직접 모터를 구동해보도록 하겠습니다.
개선점은 그 다음에 짚어보도록 하구요.
'취미 > 로봇' 카테고리의 다른 글
[아두이노] Differential Wheeled RC카 만들기 #2-3 "모터 구동/정지 함수 제작" (0) | 2021.03.02 |
---|---|
[아두이노] Differential Wheeled RC카 만들기 #2-2 "모터 데드존(Deadzone) 테스트" (0) | 2021.02.27 |
[아두이노] Differential Wheeled RC카 만들기 #2-1 "모터 회전 방향 테스트" (0) | 2021.02.27 |
[아두이노] Differential Wheeled RC카 만들기 #1-3 "신호 스케일링" (0) | 2021.02.13 |
[아두이노] Differential Wheeled RC카 만들기 #1-2 "신호 평균내기" (0) | 2021.02.11 |