找回密碼
 立即注冊(cè)

QQ登錄

只需一步,快速開(kāi)始

搜索
查看: 6302|回復(fù): 9
打印 上一主題 下一主題
收起左側(cè)

51單片機(jī)智能小車(chē)程序 原理圖與PCB文件

  [復(fù)制鏈接]
跳轉(zhuǎn)到指定樓層
樓主
藍(lán)牙遙控,循跡,避障,默認(rèn)初始為藍(lán)牙遙控功能,按數(shù)字鍵盤(pán)上面的按鍵可切換功能
Altium Designer畫(huà)的原理圖和PCB圖如下:(51hei附件中可下載工程文件)



單片機(jī)源程序如下:
  1. #include<AT89x52.H>
  2. #include <intrins.h>  

  3.         //HL-1小車(chē)驅(qū)動(dòng)接線(xiàn)定義
  4.   #define Left_moto_go     {P1_3=0,P1_4=1;}    //左邊電機(jī)向前走
  5.         #define Left_moto_back    {P1_3=1,P1_4=0;}    //左邊電機(jī)向后轉(zhuǎn)
  6.         #define Left_moto_Stop    {P1_3=0,P1_4=0;}    //左邊電機(jī)停轉(zhuǎn)                     
  7.         #define Right_moto_go     {P1_6=1,P1_7=0;}        //右邊電機(jī)向前走
  8.         #define Right_moto_back   {P1_6=0,P1_7=1;}        //右邊電機(jī)向后走
  9.         #define Right_moto_Stop   {P1_6=0,P1_7=0;}        //右邊電機(jī)停轉(zhuǎn)   
  10.   
  11.         #define  ECHO  P2_0                                   //超聲波接口定義
  12.     #define  TRIG  P2_1                                   //超聲波接口定義
  13.         #define Sevro_moto_pwm    P3_3         //接舵機(jī)信號(hào)端輸入PWM信號(hào)調(diào)節(jié)速度
  14.     #define Left_1_led        P3_7         //P3_2接四路尋跡模塊接口第一路輸出信號(hào)即中控板上面標(biāo)記為OUT1
  15.         #define Left_2_led        P3_4         //P3_3接四路尋跡模塊接口第二路輸出信號(hào)即中控板上面標(biāo)記為OUT2        

  16.     #define Right_1_led       P3_5         //P3_4接四路尋跡模塊接口第三路輸出信號(hào)即中控板上面標(biāo)記為OUT3
  17.         #define Right_2_led       P3_6         //P3_5接四路尋跡模塊接口第四路輸出信號(hào)即中控板上面標(biāo)記為OUT4
  18.         #define LEDY                P2_3
  19.         #define LEDG                P2_2
  20.         #define BEEP                P2_7

  21.         #define left     'C'
  22.     #define right    'D'
  23.         #define up       'A'
  24.     #define down     'B'
  25.         #define stop     'F'
  26.         #define Car      '1'           //手機(jī)軟件1號(hào)鍵
  27.         #define Car1     '2'           //手機(jī)軟件2號(hào)鍵
  28.         #define Beep     '5'           //手機(jī)軟件5號(hào)鍵

  29.         char code str[] =  "收到指令,向前!\n";
  30.         char code str1[] = "收到指令,向后!\n";
  31.         char code str2[] = "收到指令,向左!\n";
  32.         char code str3[] = "收到指令,向右!\n";
  33.         char code str4[] = "收到指令,停止!\n";
  34.         char code str7[] = "收到指令,報(bào)警!\n";

  35.            unsigned char pwm_val_turn  = 0;//變量定義
  36.         unsigned char push_val_turn =12;//舵機(jī)歸中,產(chǎn)生約,1.5MS 信號(hào)
  37.         unsigned int  time=0;                    //時(shí)間變量
  38.         unsigned int  timer1=0;                    //時(shí)間變量
  39.     unsigned int  timer=0;                        //延時(shí)基準(zhǔn)變量

  40.         unsigned long S=0;                                //計(jì)算出超聲波距離值
  41.     unsigned long S1=0;
  42.         unsigned long S2=0;
  43.         unsigned long S3=0;
  44.         unsigned long S4=0;

  45.         bit  flag_REC=0;                                 //串行接收標(biāo)去位
  46.         bit  flag    =0;  
  47.         bit  flag_xj =0;
  48.         bit  flag_bj =0;

  49.         unsigned char  i=0;
  50.         unsigned char  dat=0;
  51.   unsigned char  buff[5]=0;       //接收緩沖字節(jié)


  52.    
  53. /************************************************************************/        
  54. //延時(shí)函數(shù)        
  55.    void delay(unsigned int k)
  56. {   
  57.      unsigned int x,y;
  58.          for(x=0;x<k;x++)
  59.            for(y=0;y<2000;y++);
  60. }
  61. /************************************************************************/
  62. //前進(jìn)
  63.      void  run(void)
  64. {
  65.    //push_val_turn=6;          //舵機(jī)歸中
  66.          Left_moto_go ;   //左電機(jī)往前走
  67.          Right_moto_go ;  //右電機(jī)往前走
  68. }

  69. //后退
  70.      void  backrun(void)
  71. {
  72.         Left_moto_back ;   //左電機(jī)往后走
  73.         Right_moto_back ;  //右電機(jī)往后走
  74.   //push_val_turn=6;          //舵機(jī)歸中
  75.          
  76. }
  77. //左轉(zhuǎn)
  78.      void  leftrun(void)
  79. {
  80.          Left_moto_go ;   //左電機(jī)往前走
  81.          Right_moto_back ;  //右電機(jī)往前走
  82. }

  83. //右轉(zhuǎn)
  84.      void  rightrun(void)
  85. {
  86.          Left_moto_go ;   //左電機(jī)往前走
  87.          Right_moto_back ;  //右電機(jī)往前走
  88. }
  89. //STOP
  90.      void  stoprun(void)
  91. {
  92.          Left_moto_Stop ;   //左電機(jī)往前走
  93.          Right_moto_Stop ;  //右電機(jī)往前走
  94. }
  95.                 void   whistle(void)
  96. {
  97.                 BEEP=0;
  98. }
  99. /************************************************************************/
  100.      void  StartModule()                       //啟動(dòng)測(cè)距信號(hào)
  101.    {
  102.           TRIG=1;                                       
  103.           _nop_();
  104.           _nop_();
  105.           _nop_();
  106.           _nop_();
  107.           _nop_();
  108.           _nop_();
  109.           _nop_();
  110.           _nop_();
  111.           _nop_();
  112.           _nop_();
  113.           _nop_();
  114.           _nop_();
  115.           _nop_();
  116.           _nop_();
  117.           _nop_();
  118.           _nop_();
  119.           _nop_();
  120.           _nop_();
  121.           _nop_();
  122.           _nop_();
  123.           _nop_();
  124.           TRIG=0;
  125.    }
  126. /***************************************************/
  127.           void Conut(void)                   //計(jì)算距離
  128.         {
  129.           while(!ECHO);                       //當(dāng)RX為零時(shí)等待
  130.           TR0=1;                               //開(kāi)啟計(jì)數(shù)
  131.           while(ECHO);                           //當(dāng)RX為1計(jì)數(shù)并等待
  132.           TR0=0;                                   //關(guān)閉計(jì)數(shù)
  133.           time=TH0*256+TL0;                   //讀取脈寬長(zhǎng)度
  134.           TH0=0;
  135.           TL0=0;
  136.           S=(time*1.7)/100;        //算出來(lái)是CM
  137.         }
  138. /************************************************************************/
  139. //字符串發(fā)送函數(shù)
  140.           void send_str( )
  141.                    // 傳送字串
  142.     {
  143.             unsigned char i = 0;
  144.             while(str[i] != '\0')
  145.            {
  146.                 SBUF = str[i];
  147.                 while(!TI);                                // 等特?cái)?shù)據(jù)傳送
  148.                 TI = 0;                                        // 清除數(shù)據(jù)傳送標(biāo)志
  149.                 i++;                                        // 下一個(gè)字符
  150.            }        
  151.     }
  152.         
  153.                   void send_str1( )
  154.                    // 傳送字串
  155.     {
  156.             unsigned char i = 0;
  157.             while(str1[i] != '\0')
  158.            {
  159.                 SBUF = str1[i];
  160.                 while(!TI);                                // 等特?cái)?shù)據(jù)傳送
  161.                 TI = 0;                                        // 清除數(shù)據(jù)傳送標(biāo)志
  162.                 i++;                                        // 下一個(gè)字符
  163.            }        
  164.     }        

  165.                           void send_str2( )
  166.                    // 傳送字串
  167.     {
  168.             unsigned char i = 0;
  169.             while(str2[i] != '\0')
  170.            {
  171.                 SBUF = str2[i];
  172.                 while(!TI);                                // 等特?cái)?shù)據(jù)傳送
  173.                 TI = 0;                                        // 清除數(shù)據(jù)傳送標(biāo)志
  174.                 i++;                                        // 下一個(gè)字符
  175.            }        
  176.     }        
  177.                     
  178.         void send_str3()// 傳送字串
  179. {
  180.         unsigned char i = 0;
  181.         while(str3[i] != '\0')
  182.         {
  183.                 SBUF = str3[i];
  184.                 while(!TI);                                // 等特?cái)?shù)據(jù)傳送
  185.                 TI = 0;                                        // 清除數(shù)據(jù)傳送標(biāo)志
  186.                 i++;                                        // 下一個(gè)字符
  187.         }        
  188. }        
  189.         void send_str4()// 傳送字串
  190. {
  191.         unsigned char i = 0;
  192.         while(str4[i] != '\0')
  193.         {
  194.                 SBUF = str4[i];
  195.                 while(!TI);                                // 等特?cái)?shù)據(jù)傳送
  196.                 TI = 0;                                        // 清除數(shù)據(jù)傳送標(biāo)志
  197.                 i++;                                        // 下一個(gè)字符
  198.         }        
  199. }
  200.         void send_str7()// 傳送字串
  201. {
  202.         unsigned char i = 0;
  203.         while(str7[i] != '\0')
  204.         {
  205.                 SBUF = str7[i];
  206.                 while(!TI);                                // 等特?cái)?shù)據(jù)傳送
  207.                 TI = 0;                                        // 清除數(shù)據(jù)傳送標(biāo)志
  208.                 i++;                                        // 下一個(gè)字符
  209.         }        
  210. }
  211. void  COMM( void )                       
  212.   {
  213.                   push_val_turn=4;          //舵機(jī)向左轉(zhuǎn)90度
  214.                   timer=0;
  215.                   while(timer<=4000); //延時(shí)400MS讓舵機(jī)轉(zhuǎn)到其位置
  216.                   StartModule();          //啟動(dòng)超聲波測(cè)距
  217.           Conut();                           //計(jì)算距離
  218.                   S2=S;  
  219.   
  220.                   push_val_turn=8;          //舵機(jī)向右轉(zhuǎn)90度
  221.                   timer=0;
  222.                   while(timer<=4000); //延時(shí)400MS讓舵機(jī)轉(zhuǎn)到其位置
  223.                   StartModule();          //啟動(dòng)超聲波測(cè)距
  224.           Conut();                          //計(jì)算距離
  225.                   S4=S;         
  226.         

  227.                   push_val_turn=6;          //舵機(jī)歸中
  228.                   timer=0;
  229.                   while(timer<=4000); //延時(shí)400MS讓舵機(jī)轉(zhuǎn)到其位置
  230.                   StartModule();          //啟動(dòng)超聲波測(cè)距
  231.           Conut();                          //計(jì)算距離
  232.                   S1=S;         

  233.           if((S2<20)||(S4<20)) //只要左右各有距離小于,20CM小車(chē)后退
  234.                   {
  235.                   backrun();                   //后退
  236.                   timer=0;
  237.                   while(timer<=4000);
  238.                   }
  239.                   
  240.                   if(S2>S4)                 
  241.                      {
  242.                                 rightrun();          //車(chē)的左邊比車(chē)的右邊距離小        右轉(zhuǎn)        
  243.                         timer=0;
  244.                         while(timer<=4000);
  245.                      }                                      
  246.                        else
  247.                      {
  248.                        leftrun();                //車(chē)的左邊比車(chē)的右邊距離大        左轉(zhuǎn)
  249.                        timer=0;
  250.                        while(timer<=4000);
  251.                      }                                    
  252. }
  253. /************************************************************************/
  254. /*                    PWM調(diào)制舵機(jī)信號(hào)                                 */
  255. /************************************************************************/
  256. /*                    左電機(jī)調(diào)速                                        */
  257. /*調(diào)節(jié)push_val_left的值改變電機(jī)轉(zhuǎn)速,占空比            */
  258.                 void pwm_Servomoto(void)
  259. {  

  260.     if(pwm_val_turn<=push_val_turn)
  261.                Sevro_moto_pwm=1;
  262.         else
  263.                Sevro_moto_pwm=0;
  264.         if(pwm_val_turn>=200)
  265.         pwm_val_turn=0;

  266. }
  267. /***************************************************/
  268. ///*TIMER1中斷服務(wù)子函數(shù)產(chǎn)生PWM信號(hào)*/
  269.          void time1()interrupt 3   using 2
  270. {        
  271.      TH1=(65536-100)/256;          //100US定時(shí)
  272.          TL1=(65536-100)%256;
  273.          timer++;                                  //定時(shí)器100US為準(zhǔn)。在這個(gè)基礎(chǔ)上延時(shí)
  274.          pwm_val_turn++;
  275.          pwm_Servomoto();
  276. }
  277. /************************************************************************/
  278. void sint() interrupt 4          //中斷接收3個(gè)字節(jié)
  279. {

  280.     if(RI)                         //是否接收中斷
  281.     {
  282.        RI=0;
  283.        dat=SBUF;
  284.        if(dat=='O'&&(i==0)) //接收數(shù)據(jù)第一幀
  285.          {
  286.             buff[i]=dat;
  287.             flag=1;        //開(kāi)始接收數(shù)據(jù)
  288.          }
  289.        else
  290.       if(flag==1)
  291.      {
  292.       i++;
  293.       buff[i]=dat;
  294.       if(i>=2)
  295.       {i=0;flag=0;flag_REC=1 ;}  // 停止接收
  296.      }
  297.          }
  298. }
  299. /*********************************************************************/                 
  300. /*--主函數(shù)--*/
  301.         void main(void)
  302. {
  303.         TMOD=0x11;  
  304.     TH1=(65536-100)/256;          //100US定時(shí)
  305.         TL1=(65536-100)%256;
  306.         TH0=0;
  307.         TL0=0;

  308.     T2CON=0x34;
  309.         T2MOD=0x00;
  310.         RCAP2H=0xFF;
  311.         RCAP2L=0xDC;
  312.   SCON=0x50;  
  313.     PCON=0x00;

  314.   PS=1;
  315.         TR1=1;
  316.         ET1=1;
  317.         ES=1;
  318.   EA=1;  
  319.         
  320.         delay(100);
  321.     push_val_turn=6;          //舵機(jī)歸中
  322.           BEEP=1;
  323.         while(1)                                                        /*無(wú)限循環(huán)*/
  324.         {
  325.                         //BEEP=1;
  326.                   while(flag_xj)                           //循線(xiàn)標(biāo)志位
  327.                   {
  328.                                 LEDG=1;
  329.                                if(flag_REC==1)
  330.                                  {
  331.                                   stoprun();
  332.                                   break;
  333.                                  }
  334.                     
  335.                             //有信號(hào)為0  沒(méi)有信號(hào)為1
  336.               if(Left_2_led==1&&Right_1_led==1)
  337.                           run();

  338.                           else
  339.                          {                           
  340.                             if(Right_1_led==1&&Left_2_led==0)                //右邊檢測(cè)到黑線(xiàn)
  341.                                   {         
  342.                                 leftrun();
  343.                                   }
  344.                                 
  345.                                 if(Left_2_led==1&&Right_1_led==0)            //左邊檢測(cè)到黑線(xiàn)
  346.                                   {
  347.                                     rightrun();
  348.                              }
  349.                                  if(Left_2_led==0&&Right_1_led==0)            //兩邊同時(shí)檢測(cè)到黑線(xiàn)
  350.                                   {
  351.                                     stoprun();
  352.                              }
  353.                           }                                
  354.                   }

  355.                          while(flag_bj)                       /*無(wú)限循環(huán)*/
  356.            {
  357.                                 LEDY=1;
  358.                if(timer>=1000)          //100MS檢測(cè)啟動(dòng)檢測(cè)一次
  359.              {
  360.                timer=0;
  361.                    StartModule(); //啟動(dòng)檢測(cè)
  362.            Conut();                  //計(jì)算距離
  363.            if(S<20)                  //距離小于20CM
  364.                    {
  365.                    stoprun();          //小車(chē)停止
  366.                    COMM();                   //方向函數(shù)
  367.                    }
  368.                    else
  369.                    if(S>30)                  //距離大于,30CM往前走
  370.                    run();
  371.              }

  372.                          if(flag_REC==1)
  373.                         {
  374.                           push_val_turn=6;          //舵機(jī)歸中
  375.                           stoprun();
  376.                           break;
  377.                         }
  378.           }
  379.           if(flag_REC==1)                                    //
  380.            {
  381.                 flag_REC=0;
  382.                 if(buff[0]=='O'&&buff[1]=='N')        //第一個(gè)字節(jié)為O,第二個(gè)字節(jié)為N,第三個(gè)字節(jié)為控制碼
  383.                         BEEP=1;
  384.                 switch(buff[2])
  385.              {
  386.                       case up :                                                    // 前進(jìn)
  387.                           send_str( );
  388.                           flag_xj=0;
  389.                           flag_bj=0;
  390.                           run();
  391.                           break;

  392.                       case down:                                                // 后退
  393.                           send_str1( );
  394.                           flag_xj=0;
  395.                           flag_bj=0;
  396.                           backrun();
  397.                           break;

  398.                       case left:                                                // 左轉(zhuǎn)
  399.                           send_str2( );
  400.                           flag_xj=0;
  401.                           flag_bj=0;
  402.                           leftrun();
  403.                           break;

  404.                       case right:                                                // 右轉(zhuǎn)
  405.                           send_str3( );
  406.                           flag_xj=0;
  407.                           flag_bj=0;
  408.                           rightrun();
  409.                           break;

  410.                       case stop:                                                // 停止
  411.                           send_str4( );
  412.                           flag_xj=0;
  413.                           flag_bj=0;
  414.                           stoprun();
  415.                           break;

  416.                           case Car :                                                //                 
  417.                           flag_xj=1;
  418.                           break;

  419.                           case Car1 :                                                //                 
  420.                           flag_bj=1;
  421.                           break;
  422.                                 
  423.                                 case Beep:                                                //                 
  424.                                 send_str7( );
  425.                           flag_bj=0;
  426.                                 flag_xj=0;
  427.                                 whistle();
  428.                           break;
  429.              }                 
  430.          }
  431.         }
  432. }                                   
復(fù)制代碼

所有資料51hei附件下載:
藍(lán)牙小車(chē).7z (3.88 MB, 下載次數(shù): 212)

評(píng)分

參與人數(shù) 1黑幣 +50 收起 理由
admin + 50 共享資料的黑幣獎(jiǎng)勵(lì)!

查看全部評(píng)分

分享到:  QQ好友和群QQ好友和群 QQ空間QQ空間 騰訊微博騰訊微博 騰訊朋友騰訊朋友
收藏收藏12 分享淘帖 頂2 踩
回復(fù)

使用道具 舉報(bào)

沙發(fā)
ID:1000242 發(fā)表于 2022-1-6 11:35 | 只看該作者
感謝樓主 非常具有借鑒價(jià)值
回復(fù)

使用道具 舉報(bào)

板凳
ID:1010578 發(fā)表于 2022-3-15 14:42 | 只看該作者
可以給我一份原理圖嗎?
回復(fù)

使用道具 舉報(bào)

地板
ID:1010578 發(fā)表于 2022-3-15 14:49 | 只看該作者
樓主做的非常棒
回復(fù)

使用道具 舉報(bào)

5#
ID:1010578 發(fā)表于 2022-3-15 21:18 | 只看該作者
有沒(méi)有原理圖庫(kù)
回復(fù)

使用道具 舉報(bào)

6#
ID:1015712 發(fā)表于 2022-4-4 22:19 | 只看該作者
感謝,這個(gè)給予我很大的幫助
回復(fù)

使用道具 舉報(bào)

7#
ID:971889 發(fā)表于 2022-4-13 23:40 來(lái)自手機(jī) | 只看該作者
有沒(méi)有封裝庫(kù)和元件庫(kù)分享一下
回復(fù)

使用道具 舉報(bào)

8#
ID:975773 發(fā)表于 2022-4-21 15:06 | 只看該作者
感謝樓主 非常具有借鑒價(jià)值
回復(fù)

使用道具 舉報(bào)

9#
ID:297903 發(fā)表于 2022-4-22 12:16 | 只看該作者
好資料,謝謝分享!
回復(fù)

使用道具 舉報(bào)

10#
ID:656359 發(fā)表于 2022-11-17 16:15 | 只看該作者
藍(lán)牙模塊是用哪呀一款
回復(fù)

使用道具 舉報(bào)

本版積分規(guī)則

手機(jī)版|小黑屋|51黑電子論壇 |51黑電子論壇6群 QQ 管理員QQ:125739409;技術(shù)交流QQ群281945664

Powered by 單片機(jī)教程網(wǎng)

快速回復(fù) 返回頂部 返回列表