极客工坊

 找回密码
 注册

QQ登录

只需一步,快速开始

查看: 29542|回复: 5

差速转向坦克车(PS2+SPI+LCD16202)

[复制链接]
发表于 2020-3-4 21:28:57 | 显示全部楼层 |阅读模式
差速控制转向,可以用X/Y参数(这里用PS2手柄的一个摇杆)控制车辆前后、调速,转向;简化了操纵难度。
本人习惯用Promini328p,取其性价比高,体积小巧,功能够用;用74LS595实现SPI扩展并行接口;前四位驱动一个四相五线步进电机(炮塔),后四位通过754410驱动两个有刷电机。开机音乐尚没进步开发应用。
本机增加LCD1602作为人机对话,便于调试阶段检测遥控通讯。

  1. /**  
  2. Version 2020.3.2  
  3. by SJL
  4. **/
  5. #include <PS2X_lib.h>              //PS2X
  6. #include <LiquidCrystal.h>        //lcd
  7. #include "pitches.h"               //tone

  8. //LCD initial
  9. const int rs = 5, en = 4, d4 = A0, d5 = A1, d6 = A2, d7 = A3;
  10. //const int rs = A2, en = A1, d4 = A3, d5 = A4, d6 = A5, d7 = 5;数据脚皆可用模拟替代。
  11. LiquidCrystal lcd(rs, en, d4, d5, d6, d7);

  12. //74HC595 SPI initial
  13. #define latchPin 12
  14. #define clockPin 11
  15. #define dataPin 10

  16. //tone
  17. const int Speaker=3;
  18. int melody[] = {NOTE_C4, NOTE_G3, NOTE_G3, NOTE_A3, NOTE_G3, 0, NOTE_B3, NOTE_C4};    // notes in the melody:
  19. int noteDurations[] = {4, 8, 8, 4, 4, 4, 4, 4};    // note durations: 4 = quarter note, 8 = eighth note, etc.:

  20. //PS2 initial
  21. #define PS2_DAT      8      // 2019.10.20旧版本 dat、cmd 不能用模拟管脚。
  22. #define PS2_CMD      7     
  23. #define PS2_SEL      A5      
  24. #define PS2_CLK      A4      

  25. #define motorL_En12   9               //754410 PinEnable,PWMpin
  26. #define motorR_En34   6
  27. int motorDr[]={B0101,B1010,B0000};    //(-+ -+,+-+-,----)/gofront,goback,stop motorCode
  28.                                       //可调节管脚正负配置,{B1010,B0101,B0000}
  29. int L_EnValue=0, R_EnValue=0;

  30. PS2X ps2x;              // create PS2 Controller Class

  31. int PS_LX;               //PS2手柄左摇杆X轴数据 左摇杆用于行走
  32. int PS_LY;               
  33. int PS_RX;               //PS2手柄右摇杆X轴数据 右摇杆用于炮塔 Turret
  34. int PS_RY;               //暂空

  35. int error = 0;         //ps2连接正确与否的判断标志
  36. byte type = 0;         //ps2x.readType()转换判别标志     
  37. byte vibrate = 0;

  38. int carCoad=0;          //car move mode code  
  39. int F=0;                //car move value
  40. int Turn=0;             //car turn value
  41. int T=0;                //Turrent round value
  42. int Degree=1100;          //most value of turrent round  
  43. int StepNumber = 0;     //stepmotor wont moveNumber
  44. int old_Degree = 0;

  45. int StepData=0;                              //步进电机的执行编码
  46. int stepCode[] = {8, 12, 4, 6, 2, 3, 1, 9};  //8步编码
  47. int stepCodeIndex=0;                          //步编码-电机当前位于0~7的哪一步

  48. void setup() {  
  49.   lcd.begin(16, 2);                 // set up the LCD's number of columns and rows:
  50.   
  51.   lcd.print("Lx");      
  52.   lcd.setCursor(0,1);
  53.   lcd.print("Rx");  
  54.   lcd.setCursor(8,0);
  55.   lcd.write("Ly");
  56.   lcd.setCursor(8,1);
  57.   lcd.write("Ry");

  58.   pinMode(dataPin,OUTPUT);  pinMode(clockPin,OUTPUT);  pinMode(latchPin,OUTPUT);  //74HC595管脚配置  
  59.   pinMode(motorL_En12,OUTPUT);  pinMode(motorR_En34,OUTPUT);                      //电机使能管脚配置

  60.   //tone
  61.    for (int thisNote = 0; thisNote < 8; thisNote++) {
  62.       int noteDuration = 1000 / noteDurations[thisNote];
  63.       tone(Speaker, melody[thisNote], noteDuration);
  64.       int pauseBetweenNotes = noteDuration * 1.30;   // to distinguish the notes, set a minimum time between them.   
  65.                                                      // the note's duration + 30% seems to work well:
  66.       delay(pauseBetweenNotes);   
  67.       noTone(3);                                  // stop the tone playing:
  68.   }

  69.   // initialize the serial communications
  70.   Serial.begin(9600);              
  71.   delay(50);
  72.   error = ps2x.config_gamepad(PS2_CLK, PS2_CMD, PS2_SEL, PS2_DAT);
  73. }

  74. void loop() {
  75.     int number=5 ;   
  76.     ps2x.read_gamepad(false, vibrate);          //read controller and set large motor to spin at 'vibrate' speed
  77.    
  78.     /*if(ps2x.Button(PSB_START))                  //start选中
  79.       Serial.println("Start is being held");   
  80.     if(ps2x.Button(PSB_SELECT))                  //select选中
  81.       Serial.println("Select is being held");*/

  82.    PS_LX=ps2x.Analog(PSS_LX);           //把PS2手柄左摇杆X轴数据赋值PS_LX
  83.    PS_RX=ps2x.Analog(PSS_RX);           //把PS2手柄右摇杆X轴数据赋值PS_RX
  84.    PS_LY=ps2x.Analog(PSS_LY);           //把PS2手柄左摇杆Y轴数据赋值PS_LY
  85.    PS_RY=ps2x.Analog(PSS_RY);           //把PS2手柄右摇杆Y轴数据赋值PS_RY

  86.    lcd.setCursor(3,0);                  //LCD显示手柄参数
  87.    lcd.print(PS_LX);
  88.    lcd.setCursor(11,0);
  89.    lcd.print(PS_LY);
  90.    lcd.setCursor(3,1);
  91.    lcd.print(PS_RX);
  92.    lcd.setCursor(11,1);
  93.    lcd.print(PS_RY);
  94.    
  95. /******************* 行走控制 ************************/           
  96.     if(PS_LY<=125){                        //轮使能/电机运转旋向配置                  
  97.       F = map(PS_LY,125,0,90,255);        //电机使能值确定
  98.       carCoad = motorDr[0];               //各电机运行方向确定 goFront
  99.       }
  100.     else if(PS_LY>=130){
  101.       F = map(PS_LY,130,255,90,255);     
  102.       carCoad = motorDr[1];               //goBack
  103.       }
  104.      else {F=0;    carCoad=motorDr[2];}   //Stop
  105.      //转向影响旋转使能的百分比            
  106.      if(PS_LX<=125){                 //左转                     
  107.       Turn = map(PS_LX,125,0,90,40);
  108.       L_EnValue = F * Turn/100;         //转向侧电机使能值 按照百分比减弱
  109.         if(L_EnValue<30)L_EnValue=0;    //若使能值小于某值,直接定义为0;以免烧电机。
  110.       R_EnValue = F;     
  111.       }
  112.      else if(PS_LX>=130){             //右转
  113.       Turn = map(PS_LX,130,255,90,40);
  114.       L_EnValue = F;
  115.       R_EnValue = F * Turn/100;         //转向侧电机使能值 按照百分比减弱
  116.          if(R_EnValue<30)R_EnValue=0;   //若使能值小于某值,直接定义为0;以免烧电机。
  117.       }
  118.     else {                           //Turn=0;
  119.       L_EnValue = F;
  120.       R_EnValue = F;
  121.       }
  122.                        
  123.   carMove(carCoad,L_EnValue,R_EnValue,StepData); //用所得参数 调用行走子程序。
  124.   
  125.    /***************** 炮塔控制 *************************/
  126.    {      }   
  127. }  
  128.               /********************************************
  129.               走行子程序(行走模式,en_L, en_R, Turrent_StepData)
  130.                *******************************************/
  131. void carMove(int carCoad,int L_EnValue,int R_EnValue,int StepData)
  132. {                     
  133.       byte DataByte;
  134.          digitalWrite(motorL_En12,LOW);                //first turnOff every enPin
  135.          digitalWrite(motorR_En34,LOW);
  136.          
  137.       DataByte = (StepData<< 4) | carCoad;             //字节组合
  138.       //Serial.print(" StepData ");Serial.print(StepData);Serial.print(" carCoad ");Serial.println(carCoad);
  139.       
  140.       digitalWrite(latchPin, LOW);                     //数据串行输出,关断latchPin。         
  141.       shiftOut(dataPin, clockPin, MSBFIRST, DataByte); //逐个字节发送
  142.       //delay(5);   
  143.       digitalWrite(latchPin, HIGH);                    //打开latchPin,数据并行输出
  144.       
  145.         analogWrite(motorL_En12, L_EnValue);   
  146.         analogWrite(motorR_En34, R_EnValue);      
  147. }

复制代码
回复

使用道具 举报

发表于 2020-3-8 16:55:58 | 显示全部楼层
把接线和图片都发出来吧
回复 支持 1 反对 0

使用道具 举报

发表于 2020-3-12 10:18:13 | 显示全部楼层
本帖最后由 allen727hk 于 2020-3-12 10:33 编辑

有影片看嗎?
回复 支持 反对

使用道具 举报

发表于 2020-3-12 12:24:52 来自手机 | 显示全部楼层
記起來! 記起來!!    空閒再來研究一下~
回复 支持 反对

使用道具 举报

发表于 2020-3-24 17:56:52 | 显示全部楼层
有接线图吗?
回复 支持 反对

使用道具 举报

发表于 2020-4-2 10:02:47 | 显示全部楼层
有接线图吗?   
回复 支持 反对

使用道具 举报

您需要登录后才可以回帖 登录 | 注册

本版积分规则 需要先绑定手机号

Archiver|联系我们|极客工坊

GMT+8, 2024-4-24 01:01 , Processed in 0.041313 second(s), 23 queries .

Powered by Discuz! X3.4 Licensed

Copyright © 2001-2021, Tencent Cloud.

快速回复 返回顶部 返回列表