오늘 둘째놈이 아빠방에 고장나서 방치되어있는 자기 지프차를 보더니 "아빠 이거 고쳐줘잉~" 이런다. 요새 계속되는 회사 야근때문에 손을 거의 데지 못하고 있었는데, 오늘 좀더 진도를 나가본다.
오늘은 수신기쪽에 모터와 서보를 붙여놓고 실제로 돌아가는지 테스트를 해봤다.
좌측이 송신기쪽, 우측이 수신기쪽이다.
수신기쪽에 파란색 작은 SG90 이 스티어링 서보이고, 스탠다드 사이즈의 서보처럼 생긴것은 서보가 아니고 그냥 감속기어 달린 모터이다.
좌측의 송신기쪽 스틱 하나로 스티어링과 서보를 모두 제어하게 설계하였는데, 이게 문제가 좀 있다. 스틱이 하나이다보니 스로틀+스티어링이 동시에 제어되기 힘든구조이다.
앞으로 밀면서 옆으로 밀면 앞으로 밀 수가 없다. 저 스틱의 움직이는 범위가 사각형이 아니라 원형이기 때문에 왼쪽+위 이런게 안된다. 우선 1차 버전은 심플하게 이렇게 만들고 다음 버전에서는 스틱을 분리하던지 건타입을 어떻게 해서든 만들어봐야하겠다.
움직이는 동영상 하나 올려본다.
이번에 수정한 코드이다. 좀더 설계를하고 만들어야 하는데, 막코딩으로 가고있다.
송신기 코드는 이전과 같고, 수신기 코드만 올려본다.
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 | /* Name: SX_RF24RX.ino Created: 10/30/2015 11:12:14 PM Author: korean44 */ // the setup function runs once when you press reset or power the board #include <Servo.h> #include "receiver.h" #include <SPI.h> #include <RF24_config.h> #include <RF24.h> #include <printf.h> #include <nRF24L01.h> #include "../joon_nrf24l01_config.h" #include "../joon_transmitter_packet.h" #define __DEBUG RF24 radio(PIN_CE, PIN_CSN); TX_DATA data; // 각 출력 채널의 출력 핀 번호 및 DIGITAL, ANALOG 타입 설정 CHANNEL g_outputChannels[MAX_CHANNELS] = { {1,0x00000003, SERVO,0,1023,511} , {2, 0x00000605, L293,0,1023,511} ,{1,0x00000004, DIGITAL,0,0,0} ,{1, 0x00000009, PWM,0,0,0} ,{1,0x00000013, DIGITAL,0,0,0} ,{1, 0x00000012, DIGITAL,0,0,0} }; Servo servoSteering; void setup() { Serial.begin(115200); while (!Serial); Serial.println( "RX Serial Ready" ); readyServos(NULL); radio.begin(); radio.setPALevel(RF24_PA_LOW); radio.openReadingPipe(1, RX_READ_CHANNEL); radio.startListening(); } // the loop function runs over and over again until power down or reset void loop() { unsigned long start_wait_us = micros(); bool timeout = false ; while (!radio.available()) { if (micros() - start_wait_us > RF24_TIMEOUT_US) { timeout = true ; Serial.println( "--TIMEOUT--" ); break ; } } if (!timeout) { radio.read(&data, sizeof (data)); unsigned long read_time_us = micros(); #ifdef DEBUG Serial.print( "Steering : " ); Serial.print(data.channel[0]); Serial.print( "/ Accel : " ); Serial.print(data.channel[1]); Serial.print( "/ CH3 : " ); Serial.print(data.channel[2]); Serial.print( "/ CH4 : " ); Serial.print(data.channel[3]); Serial.print( "/ CH5 : " ); Serial.print(data.channel[4]); Serial.print( "/ CH6 : " ); Serial.println(data.channel[5]); Serial.print( "== Receive Delay : " ); Serial.print(read_time_us - start_wait_us); Serial.println( " uS" ); #endif if (validateTx(&data)) procChannels(&data); } } bool validateTx(LPTX_DATA lpTx) { return true ; } void readyServos(CHANNEL* channels) { servoSteering.attach(3); /* -- 향후에 SERVO 출력모드인 채널들을 읽어서 세팅하기 for (int curChannel = 0; curChannel < MAX_CHANNELS; curChannel++) { if (channels[curChannel].outMode == SERVO) { } }*/ } void procChannels(LPTX_DATA lpTx) { LPCHANNEL pCurChannel = NULL; int inputChannels = sizeof (lpTx->channel) / sizeof ( short ); for ( int curChannel = 0; curChannel < MAX_CHANNELS; curChannel++) { if (curChannel < inputChannels) pCurChannel = &g_outputChannels[curChannel]; else break ; channelWrite(pCurChannel, lpTx->channel[curChannel]); } } void channelWrite(LPCHANNEL lpChannel, int inputValue) { for ( int nIndex = 0; nIndex < lpChannel->pins_used; nIndex++) { int curPin = (lpChannel->pins >> (8 * nIndex) ) & 0xFF; if (lpChannel->outMode == DIGITAL) { digitalWrite(curPin, inputValue); } else if (lpChannel->outMode == SERVO) { // 현재는 3번채널에 서보 1개 고정. inMin ~ inMax 를 map 함수로 하여 0~255 출력 값으로 맵핑 함 int angle = map(inputValue, lpChannel->inMin, lpChannel->inMax, 0, 180); #ifdef __DEBUG Serial.print( "Angle : " ); Serial.println(angle); #endif servoSteering.write(angle); } else if (lpChannel->outMode == PWM) { int pwm = map(inputValue, lpChannel->inMin, lpChannel->inMax, 0, 255); #ifdef __DEBUG #endif analogWrite(curPin, pwm); } else if (lpChannel->outMode == L293) { int pwm = 0; if (nIndex == 0) if (inputValue <= lpChannel->inCenter) pwm = 0; else pwm = map(inputValue, lpChannel->inCenter, lpChannel->inMax, 0, 255); else if (inputValue >= lpChannel->inCenter) pwm = 0; else { pwm = map(inputValue, lpChannel->inMin, lpChannel->inCenter, 0, 255); pwm = 255 - pwm; } #ifdef DEBUG Serial.print(nIndex); Serial.print( " c " ); Serial.print(curPin); Serial.print( " / p " ); Serial.println(pwm); #endif analogWrite(curPin, pwm); } } } |
반응형
'Software Development > IoT, Arduino, RasberryPi' 카테고리의 다른 글
버튼과 Bounce #1 - Bouncing 현상 들여다보기 (0) | 2015.11.15 |
---|---|
아두이노 송수신기 만들기 #수신기 회로 (0) | 2015.11.08 |
아두이노 송수신기 만들기 #조이스틱 연결 (1) | 2015.11.07 |
아두이노 송수신기 만들기 #통신모듈 테스트 (3) | 2015.10.31 |
NRF24L01 모듈 #2 - 소프트웨어 (4) | 2015.10.31 |