改进舵机盘
USB下载口,程序烧录,写进板子就是通过它连接电脑。
升压机,输入3.5-6v,输出30万-60万的高压电,可以击穿空气,测试通过,具体用途待定。
Uno板,机器人主板,用箱子安装,可以用杜邦线再接一层到扩展板上,通过扩展板去接面板板,面包板放到一个盒子中,按功能分层梯度排列,这样
充分发挥面包板的方便管理优势,又可以去除它松动的缺点,一举两得。
/** * author wjf * date 2017/12/30 14:23 * 新版测试品代码备份 * 每个长注释中的代码,都可以单独的模块运用 */ ////////////////引入头文件////////////////////////////////////////////////// #include <IRremote.h> // 红外 #include <Servo.h> //舵机 //通用字符串库 #include <stdio.h> #include <string.h> #include <stdlib.h> //LCD #include <LiquidCrystal_I2C.h> //LCD #include <Wire.h> #include <LCD.h> /** * 定义LCD对象, * 第一个参数0x20需要先扫描I2C地址扫描代码地址: * http://www.cnblogs.com/SATinnovation/p/8047240.html * 后面的暂时不知道什么意思,可以这么直接用 */ LiquidCrystal_I2C lcd(0x20,2,1,0,4,5,6,7); //////////////////////定义LCD方法//////////////////////////////////////////////////////////// void initLCD(){ lcd.begin (16,2); // for 16 x 2 LCD module lcd.setBacklightPin(3,POSITIVE); lcd.setBacklight(HIGH); } void wjf_setLcd(char *str){//设置LCD显示的字符串 lcd.home (); // set cursor to 0,0 lcd.print(str); lcd.setCursor (0,1); // go to start of 2nd line //lcd.print(millis()); //delay(1000); lcd.setBacklight(LOW); // Backlight off delay(250); lcd.setBacklight(HIGH); // Backlight on delay(1000); } /////////////电机/////////////////////////////////// //电机PIN const int IN1=5; const int IN2=4; const int ENA=6; const int IN3=8; const int IN4=7; const int ENB=9; //电机速度 int speed = 100; ///////////定义左右舵机//////////////////////////////// //左右转舵机 const int IN10=10; Servo myservo; int pos = 90; void getLeftAndRight_left() { for (pos = 30; pos < 90; pos += 1) { myservo.write(pos); delay(15); } } void getLeftAndRight_center() { Serial.println(110); Serial.println(pos); if (pos == 90) { for (pos = 90; pos > 30; pos -= 1) { myservo.write(pos); delay(15); } }else if(pos == -30){ for (pos = -30; pos < 30; pos += 1) { myservo.write(pos); delay(15); } } } void getLeftAndRight_right() { for (pos = 30; pos > -30; pos -= 1) { myservo.write(pos); delay(15); } } void initLeftAndRight() { myservo.attach(IN10); myservo.write(pos); } ///////////定义上下舵机//////////////////////////////// //上下转舵机 const int IN13=13; Servo myservo2; int pos2 = 90; void getLeftAndRight_left2() { for (pos2 = 30; pos2 < 90; pos2 += 1) { myservo2.write(pos2); delay(15); } } void getLeftAndRight_center2() { Serial.println(110); Serial.println(pos2); if (pos2 == 90) { for (pos2 = 90; pos2 > 30; pos2 -= 1) { myservo2.write(pos2); delay(15); } }else if(pos2 == -30){ for (pos2 = -30; pos2 < 30; pos2 += 1) { myservo2.write(pos2); delay(15); } } } void getLeftAndRight_right2() { for (pos2 = 30; pos2 > -30; pos2 -= 1) { myservo2.write(pos2); delay(15); } } void initLeftAndRight2() { myservo2.attach(IN13); myservo2.write(pos2); } //红外接收 int RECV_PIN = 3; IRrecv irrecv(RECV_PIN); decode_results results; long control[7][3] = {//遥控器矫正数字 {16580863, 16613503, 16597183}, {16589023, 16621663, 16605343}, {16584943, 16617583, 16601263}, {16593103, 16625743, 16609423}, {16582903, 16615543, 16599223}, {16591063, 16623703, 16607383}, {16586983, 16619623, 16603303} }; //初始化电机PIN void initMotor(){ pinMode(IN1, OUTPUT); pinMode(IN2, OUTPUT); pinMode(ENA, OUTPUT); pinMode(IN4, OUTPUT); pinMode(IN3, OUTPUT); pinMode(ENB, OUTPUT); } //初始化红外接收 void initIR(){ irrecv.enableIRIn(); } ////////////////定义超声波////////////////////////////////////////////// const int trigPin = 12;//触发针脚 const int echoPin = 11;//回声针脚 float distance;//存放距离 //初始化超声波针脚 void initUltrasonic(){ pinMode(trigPin, OUTPUT); pinMode(echoPin, INPUT); } //获取距离 void getDistance(){ // 产生一个10us的高脉冲去触发trigPin digitalWrite(trigPin, LOW); delayMicroseconds(2); digitalWrite(trigPin, HIGH); delayMicroseconds(10); digitalWrite(trigPin, LOW); // 检测脉冲宽度,并计算出距离 distance = pulseIn(echoPin, HIGH) / 58.00; Serial.print(distance); Serial.print("cm"); } void setup() { Serial.begin(9600); //初始电机 initMotor(); //初始化红外接收 initIR(); //初始化左右转舵机 initLeftAndRight(); //初始化上下转舵机 initLeftAndRight2(); //初始化LCD initLCD(); wjf_setLcd("Hello world"); } void loop() { Motor1_Backward(speed);//电机反转,PWM调速 Motor2_Backward(speed);//电机反转,PWM调速 if (irrecv.decode(&results)) { Serial.println(results.value, HEX);//以16进制换行输出接收代码 if (results.value == 4294967295) { //long click } else { if (results.value == control[0][0]) { Motor1_Brake();//停止电机1 Motor2_Brake();//停止电机2 Motor1_Backward(speed);//电机反转,PWM调速 } else if (results.value == control[0][1]) {//上 Motor1_Backward(speed);//电机反转,PWM调速 Motor2_Backward(speed);//电机反转,PWM调速 } else if (results.value == control[0][2]) { Motor1_Brake();//停止电机1 Motor2_Brake();//停止电机2 Motor2_Backward(speed);//电机反转,PWM调速 } else if (results.value == control[1][0]) {//左 } else if (results.value == control[1][1]) {//中 Motor1_Brake();//停止电机1 Motor2_Brake();//停止电机2 } else if (results.value == control[1][2]) {//右 } else if (results.value == control[2][0]) { Motor1_Brake();//停止电机1 Motor2_Brake();//停止电机2 Motor1_Forward(speed);//电机正转,PWM调速 } else if (results.value == control[2][1]) {//下 Motor1_Forward(speed);//电机正转,PWM调速 Motor2_Forward(speed);//电机正转,PWM调速 } else if (results.value == control[2][2]) { Motor1_Brake();//停止电机1 Motor2_Brake();//停止电机2 Motor2_Forward(speed);//电机正转,PWM调速 } else if (results.value == control[3][0]) {//0 } else if (results.value == control[3][1]) { } else if (results.value == control[3][2]) {//st } else if (results.value == control[4][0]) {//1 } else if (results.value == control[4][1]) {//2 } else if (results.value == control[4][2]) {//3 } else if (results.value == control[5][0]) {//4 } else if (results.value == control[5][1]) {//5 } else if (results.value == control[5][2]) {//6 } else if (results.value == control[6][0]) {//7 getDistance();//获取超声波测得的距离 } else if (results.value == control[6][1]) {//8 getLeftAndRight_center(); } else if (results.value == control[6][2]) {//9 Serial.println(110); getLeftAndRight_left(); } } irrecv.resume(); // 接收下一个值 } delay(100); } void Motor1_Forward(int Speed) //电机1正转,Speed值越大,电机转动越快 { digitalWrite(IN1,HIGH); digitalWrite(IN2,LOW); analogWrite(ENA,Speed); } void Motor1_Backward(int Speed) //电机1反转,Speed值越大,电机转动越快 { digitalWrite(IN1,LOW); digitalWrite(IN2,HIGH); analogWrite(ENA,Speed); } void Motor1_Brake() //电机1刹车 { digitalWrite(IN1,LOW); digitalWrite(IN2,LOW); } void Motor2_Forward(int Speed) //电机2正转,Speed值越大,电机转动越快 { digitalWrite(IN3,HIGH); digitalWrite(IN4,LOW); analogWrite(ENB,Speed); } void Motor2_Backward(int Speed) //电机2反转,Speed值越大,电机转动越快 { digitalWrite(IN3,LOW); digitalWrite(IN4,HIGH); analogWrite(ENB,Speed); } void Motor2_Brake() { digitalWrite(IN3,LOW); digitalWrite(IN4,LOW); }
PIn:
3 接收
4 5 6 7 8 9 电机
10 左右舵
超声波:
11 echo
12 trig
13 上下舵
A口:
Lcd:
VCC
GND
scl A5
SDA A4
正面朝上,左边从上到下数,按照顺序是Vcc GND SCL SDA