Продолжение…… (Начало 1 )
Гусеницы,платформа,двигатели Tamiya
Автономное питание 4х1,5В батарейки в держателе батареи 4-AA
+ куча деталей из китайского конструктора
Для подключения двигателей микросхема L293N
Управление скоростью движения — подачей ШИМ на входы ENABLE1, ENABLE2 микросхемы L293N
мин. скорость подбирается (при подаче питания на моторы +5В — это 130 — при меньших не двигается)
плавность поворота регулируется разностью скоростей моторов
поворот на месте — моторы крутятся в разные стороны (здесь тоже регулируем скорость вращения)
Для хранения текущего состояния моторов
struct POZ // структура для хранения статусов моторов { int poz1; // позиция для 1 мотора int poz2; // позиция для 2 мотора int direction12; // направление до поворота };
Все данные о скоростях, направлениях движения,
хранятся в массиве arrpoz[9][17]
// массив возможных состояний моторов // max down -> min down -> stop -> min up -> max up int arrpoz[9][17]={ // in1 первого мотора {0,0,0,0,0,0,0,0,1,1,1,1,1,1,1}, // in2 первого мотора {1,1,1,1,1,1,1,0,0,0,0,0,0,0,0}, // скорости (enable1) первого мотора {250,230,210,190,170,150,130,0,130,150,170,190,210,230,250}, // in3 второго мотора {0,0,0,0,0,0,0,0,1,1,1,1,1,1,1}, // in4 второго мотора {1,1,1,1,1,1,1,0,0,0,0,0,0,0,0}, // скорости (enable2) второго мотора {250,230,210,190,170,150,130,0,130,150,170,190,210,230,250}, // скорость++ {0,-1,-1,-1,-1,-1,-1,0,1,1,1,1,1,1,0}, // скорость-- {-1,-1,-1,-1,-1,-1,-1,0,1,1,1,1,1,1,1}, // кружение влево-вправо {14,12,10,8,6,4,2,0,-2,-4,-6,-8,-10,-12,-14} };
Начальная инициализация
POZ POZ12={7,7,7};
— in1=0
— in2=0
— enable1=0;
— in3=0;
— in4=0;
— enable2=0;
При получении кодов от пульта происходит преобразование позиции
в процедуре go12();
Вот весь код
// #include <IRremote.h> //вход ИК приемника int RECV_PIN = 2; IRrecv irrecv(RECV_PIN); decode_results results; unsigned long ir_dt, old_ir; long ir_kod; unsigned long ir_time1, ir_time2; // коды клавиш ИК пульта (marmitek) #define FORWARD 1936 #define BACK 3984 #define SPEED_UP 144 //ch+ #define SPEED_DOWN 2192 //ch- #define LEFT 3472 #define RIGHT 1424 #define CIRCLE_LEFT 3216 //vol+ #define CIRCLE_RIGHT 1168 //vol- #define STOP 2320 //0 // состояние моторов робота struct POZ // структура для хранения статусов моторов { int poz1; // позиция для 1 мотора int poz2; // позиция для 2 мотора int direction12; // направление до поворота }; // моторы struct MOTOR // структура для хранения номеров pin-ов, к которым подключены моторчики { int in1; // INPUT1 int in2; // INPUT2 int enable; // ENABLE1 }; // определяем порты, к которым подключены моторчики MOTOR MOTOR1 = { 13, 12, 5 }; MOTOR MOTOR2 = { 7, 8, 6 }; // начальная позиция робота // 1,2 мотор - выключены POZ POZ12={7,7,7}; // массив возможных состояний моторов // max down -> min down -> stop -> min up -> max up int arrpoz[9][17]={ // in1 первого мотора {0,0,0,0,0,0,0,0,1,1,1,1,1,1,1}, // in2 первого мотора {1,1,1,1,1,1,1,0,0,0,0,0,0,0,0}, // скорости (enable1) первого мотора {250,230,210,190,170,150,130,0,130,150,170,190,210,230,250}, // in3 второго мотора {0,0,0,0,0,0,0,0,1,1,1,1,1,1,1}, // in4 второго мотора {1,1,1,1,1,1,1,0,0,0,0,0,0,0,0}, // скорости (enable2) второго мотора {250,230,210,190,170,150,130,0,130,150,170,190,210,230,250}, // скорость++ {0,-1,-1,-1,-1,-1,-1,0,1,1,1,1,1,1,0}, // скорость-- {-1,-1,-1,-1,-1,-1,-1,0,1,1,1,1,1,1,1}, // кружение влево-вправо {14,12,10,8,6,4,2,0,-2,-4,-6,-8,-10,-12,-14} }; void setup() { // последовательный порт Serial.begin(9600); // включить приемник irrecv.enableIRIn(); // прерывания для ИК ir_time1=0;ir_time2=0; attachInterrupt(0, get_ir_kod, FALLING); // настраиваем выводы для моторов pinMode(MOTOR1.in1, OUTPUT); pinMode(MOTOR1.in2, OUTPUT); pinMode(MOTOR2.in1, OUTPUT); pinMode(MOTOR2.in2, OUTPUT); // начальная позиция - робот стоит go12(POZ12.poz1,POZ12.poz2); } void loop() { // обработка кода нажатия if(ir_kod>0) { ir_go(ir_kod); ir_kod=0; } } // получить код переданный с ИК пульта void get_ir_kod() { detachInterrupt(0); // отключить прерывание 0 if (irrecv.decode(&results)) { if (results.value > 0 && results.value < 0xFFFFFFFF) { ir_dt = results.value; ir_time2=millis(); if (ir_time2-ir_time1>1000) {ir_kod = ir_dt;ir_time1=ir_time2;} else ir_kod = 0; } irrecv.resume(); } attachInterrupt(0, get_ir_kod, CHANGE); } // переустановка моторов void go12(int poz1,int poz2) { digitalWrite(MOTOR1.in1, arrpoz[0][poz1]); digitalWrite(MOTOR1.in2, arrpoz[1][poz1]); analogWrite(MOTOR1.enable, arrpoz[2][poz1]); digitalWrite(MOTOR2.in1, arrpoz[3][poz2]); digitalWrite(MOTOR2.in2, arrpoz[4][poz2]); analogWrite(MOTOR2.enable, arrpoz[5][poz2]); } // обработка кода нажатия void ir_go(long kod) { Serial.println(kod); switch(kod) { case FORWARD : // направление вперед POZ12.direction12=max(POZ12.direction12,8); POZ12.poz1=POZ12.direction12; POZ12.poz2=POZ12.direction12; go12(POZ12.poz1,POZ12.poz2); break; case BACK : // направление назад POZ12.direction12=min(POZ12.direction12,6); POZ12.poz1=POZ12.direction12; POZ12.poz2=POZ12.direction12; go12(POZ12.poz1,POZ12.poz2); break; case SPEED_UP : // скорость++ POZ12.direction12=POZ12.direction12+arrpoz[6][POZ12.direction12]; POZ12.poz1=POZ12.direction12; POZ12.poz2=POZ12.direction12; go12(POZ12.poz1,POZ12.poz2); break; case SPEED_DOWN : // скорость-- POZ12.direction12=POZ12.direction12-arrpoz[7][POZ12.direction12]; POZ12.poz1=POZ12.direction12; POZ12.poz2=POZ12.direction12; go12(POZ12.poz1,POZ12.poz2); break; case LEFT : // влево if(POZ12.direction12>6) { POZ12.poz1=POZ12.poz1-1;POZ12.poz1=max(POZ12.poz1,0); POZ12.poz2=POZ12.direction12; } else { POZ12.poz1=POZ12.poz1+1;POZ12.poz1=min(POZ12.poz1,14); POZ12.poz2=POZ12.direction12; } go12(POZ12.poz1,POZ12.poz2); break; case RIGHT : // вправо if(POZ12.direction12>6) { POZ12.poz2=POZ12.poz2-1;POZ12.poz2=max(POZ12.poz2,0); POZ12.poz1=POZ12.direction12; } else { POZ12.poz2=POZ12.poz2+1;POZ12.poz2=min(POZ12.poz2,14); POZ12.poz1=POZ12.direction12; } go12(POZ12.poz1,POZ12.poz2); break; case CIRCLE_RIGHT : // кружение вправо POZ12.poz1=POZ12.direction12; POZ12.poz2=POZ12.direction12+arrpoz[8][POZ12.direction12]; go12(POZ12.poz1,POZ12.poz2); break; //case 3216 : // кружение влево case CIRCLE_LEFT : // кружение влево POZ12.poz1=POZ12.direction12+arrpoz[8][POZ12.direction12]; POZ12.poz2=POZ12.direction12; go12(POZ12.poz1,POZ12.poz2); break; case STOP : // стоп POZ12.poz1=7; POZ12.poz2=7; POZ12.direction12=7; go12(POZ12.poz1,POZ12.poz2); break; default: break; } }
Продолжение …. Часть 3