قسم الميكروكنترولر والروبوت ودوائر الاتصال بالحاسب الالي قسم المتحكمات الـ microcontroller و المعالجات microprocessor و التحكم الرقمي بالكمبيوتر CNC والانظمة الآلية والروبوت Robots

أدوات الموضوع

ahmadazez
:: مهندس جيد ::
تاريخ التسجيل: Mar 2009
المشاركات: 253
نشاط [ ahmadazez ]
قوة السمعة:0
قديم 26-02-2019, 11:36 PM المشاركة 1   
افتراضي حساس المسافة Ultrasonic Twitter FaceBook Google+



برنامج حساس المسافة لحساب المسافة وتنفيذ اوامر معينة تبعا للمسافة او استخدامها في دوائر الروبوت

https://up.top4top.net/downloadf-1152xwxmh1-rar.html

https://f.top4top.net/m_11522axaf2.mp4



كود:
#include <mega8.h>
#include <stdlib.h>
#include <delay.h>

int timer1=0;
unsigned char str[5]; 
unsigned char timer=0,conter=0,w=0,tcnt=0; 
unsigned long  conter2=0;
float rising=0,result=0;


#define A PORTB.1    //                     B  اعادة تسمية لاقطاب البورت  
#define B PORTB.2    // من اجل استخدامها لاخراج البيانات على وحدات الاظهار
#define C PORTB.3
#define D PORTB.4
#define E PORTB.5
#define F PORTB.6
#define G PORTB.7 

#define out1 PORTC.1  //  C اعادة تسمية لاقطاب البورت 
#define out2 PORTC.2  // لتفعيل وحدة الاظهار المطلوبة
#define out3 PORTC.3
#define out4 PORTC.4  


    // External Interrupt 1 service routine
    interrupt [EXT_INT1] void ext_int1_isr(void)   //                 خدمة المقاطعة الخارجية تعمل عند اي تغير 
    {                                              //  ATmega8 لحالة قطب المقاطعة على الرجل رقم 11 من المتحكم 
         w++;
          if(w==1)              //     تشغيل التايمر زيرو عند ورود اول مقاطعة 
            {                   // اي عند بداية اكتشاف ارتداد الموجة الصوتية من الحساس
              
              TCCR0=0x03;
              TCNT0=0x83;
            }
           ////////////////////////////////////// 
           if(w==2)        //ايقاف التايمر عن العد عند انتهاء الموجة الصوتية 
            {             //                           وحساب معادلة المسافة
              
              tcnt=TCNT0; 
              TCCR0=0x00;
              
              rising=((conter2*124)+(tcnt-0x83)); // قيمة عداد مقاطعات التايمر مضروب بعدد العدات المتبقية من سجل التايمر ومضاف اليها عدد العدات الموجودة في سجل التايمر اذا وردة اشارة الحساس وكان متبقي قيمة في السجل قبل حدوث اخر مقاطعة             
              rising=rising*0.000806;         //زمن كل عدة من التايمر هي8.06 ميكرو ثانية
               result=(rising*340)/2;        //ضرب زمن التايمر المستخلص بسرعة الصوت للحصول على المسافة
               ftoa(result,0,str);
               str[0]=str[0]-48;
               str[1]=str[1]-48;
               str[2]=str[2]-48;
               str[3]=str[3]-48; 
              
               tcnt=0;
               rising=0;
               conter2=0;
               
            }        
    }

// Timer 0 overflow interrupt service routine
    interrupt [TIM0_OVF] void timer0_ovf_isr(void)   //مقاطعة التايمر تحدث كل 1 ميلي ثانية
    {
     
     
     TCNT0=0x83;        //ابتداء العد في سجل التايمر من هذا الرقم الى 256 وهي قيمة طفحان التايمر زيرو للحصول على زمن 1 ميلي ثانية 
     conter2++;        //متغير يزداد مرة عند كل مقاطعة لحساب كم مقاطعة حدثت اثناء انتظار اشارة الحساس
    }

// Declare your global variables here

    // Timer1 overflow interrupt service routine
    interrupt [TIM1_OVF] void timer1_ovf_isr(void)  //مقاطعة التايمر 1 تحدث كل 2 ميلي ثانية لحساب اوقات نحتاجها ضمن البرنامج
    {
    // Place your code here
       TCNT1H=0xFF05 >> 8;
       TCNT1L=0xFF05 & 0xff; 
       
        timer++;
        timer1++;      
       
    }

void  out(unsigned char O)
       {   
          switch (O)       //لتفعيل وحدة الاظهار 
           { 
            
            case 0: out1=0;out2=1;out3=1;out4=1; break;  
            case 1: out1=1;out2=0;out3=1;out4=1; break;
            case 2: out1=1;out2=1;out3=0;out4=1; break;
            case 3: out1=1;out2=1;out3=1;out4=0; break;
           }; 
        }   
         
void data(unsigned char dat) 
        {
           switch (dat)      // لاخراج البيانات على وحدات الاظهار
            {   
             case 0: A=1;B=1;C=1;D=1;E=1;F=1;G=0; break;  
             case 1: A=0;B=1;C=1;D=0;E=0;F=0;G=0; break;
             case 2: A=1;B=1;C=0;D=1;E=1;F=0;G=1; break;
             case 3: A=1;B=1;C=1;D=1;E=0;F=0;G=1; break;
             case 4: A=0;B=1;C=1;D=0;E=0;F=1;G=1; break;
             case 5: A=1;B=0;C=1;D=1;E=0;F=1;G=1; break;
             case 6: A=1;B=0;C=1;D=1;E=1;F=1;G=1; break;
             case 7: A=1;B=1;C=1;D=0;E=0;F=0;G=0; break;
             case 8: A=1;B=1;C=1;D=1;E=1;F=1;G=1; break;
             case 9: A=1;B=1;C=1;D=1;E=0;F=1;G=1; break;
             default: A=0;B=0;C=0;D=0;E=0;F=0;G=0; 
            }; 
        }
        
 
            
void main(void)
{
// Declare your local variables here

// Input/Output Ports initialization
// Port B initialization
// Func7=In Func6=In Func5=In Func4=In Func3=In Func2=In Func1=In Func0=In 
// State7=T State6=T State5=T State4=T State3=T State2=T State1=T State0=T 
PORTB=0x00;
DDRB=0xFF;

// Port C initialization
// Func6=Out Func5=Out Func4=Out Func3=Out Func2=Out Func1=Out Func0=Out 
// State6=0 State5=0 State4=0 State3=0 State2=0 State1=0 State0=0 
PORTC=0x00;
DDRC=0x7F;

// Port D initialization
// Func7=Out Func6=In Func5=Out Func4=Out Func3=In Func2=In Func1=In Func0=In 
// State7=0 State6=T State5=0 State4=0 State3=T State2=T State1=T State0=T 
PORTD=0x00;
DDRD=0xF0;

// Timer/Counter 0 initialization
// Clock source: System Clock
// Clock value: 125.000 kHz
TCCR0=0x00;
TCNT0=0x00;

// Timer/Counter 1 initialization
// Clock source: System Clock
// Clock value: 125.000 kHz
// Mode: Normal top=0xFFFF
// OC1A output: Discon.
// OC1B output: Discon.
// Noise Canceler: Off
// Input Capture on Falling Edge
// Timer1 Overflow Interrupt: On
// Input Capture Interrupt: Off
// Compare A Match Interrupt: Off
// Compare B Match Interrupt: Off
TCCR1A=0x00;
TCCR1B=0x03;
TCNT1H=0xFF;
TCNT1L=0x05;
ICR1H=0x00;
ICR1L=0x00;
OCR1AH=0x00;
OCR1AL=0x00;
OCR1BH=0x00;
OCR1BL=0x00;

// External Interrupt(s) initialization
// INT0: Off
// INT1: On
// INT1 Mode: Any change
GICR|=0x80;
MCUCR=0x04;
GIFR=0x80;

// Timer(s)/Counter(s) Interrupt(s) initialization
TIMSK=0x05;

// Analog Comparator initialization
// Analog Comparator: Off
// Analog Comparator Input Capture by Timer/Counter 1: Off
ACSR=0x80;
SFIOR=0x00;

#asm("sei")

while (1)
      {
        
           
        if(timer1>=125)   // بداية ارسال النبضة تتكرر كل ربع ثانية
        
          { 
            
            w=0;
            timer1=0;          
            PORTD.4=1;
            delay_us(15);
            PORTD.4=0;
             
           }
           //////////////////////////////////////  
                   
           ////////////////////////////////////   
           
          if(timer==0)     // اظهار النتيجة على وخدات الاظهار
          
           {conter=0; 
            out1=1,out2=1,out3=1,out4=1; 
            data(str[0]);      
            out(conter);           
           } 
           
         if(timer==2)
             
           { conter=1; 
             out1=1,out2=1,out3=1,out4=1;
             if(result<10)data(11);
             else data(str[1]);     
             out(conter);
            }
            
         if(timer==4)
            
           { conter=2; 
             out1=1,out2=1,out3=1,out4=1; 
             if(result<100)data(11);           
             else data(str[2]);     
             out(conter);
           }
           
         if(timer==6)
            
           { conter=3; 
             out1=1,out2=1,out3=1,out4=1; 
             data(11);     
             out(conter);
             
           }   
          
           if(timer>=8)
            { 
             conter=0;             
             timer=0; 
             
            }    
         ///////////////////////////////////////////////////    
          if(result>10&&result<50)PORTD.5=1;     //مثال لاضائة ليدات عند مسافات معينة
          else PORTD.5=0;  
          
          if(result>51&&result<100)PORTD.6=1;
          else PORTD.6=0;
          
          if(result>101&&result<200)PORTD.7=1;
          else PORTD.7=0;
          
      }  
      
}

اعلانات
إضافة رد

العلامات المرجعية

«     الموضوع السابق       الموضوع التالي    »
أدوات الموضوع

الانتقال السريع إلى


الساعة معتمدة بتوقيت جرينتش +3 الساعة الآن: 05:06 PM
موقع القرية الالكترونية غير مسؤول عن أي اتفاق تجاري أو تعاوني بين الأعضاء
فعلى كل شخص تحمل مسئولية نفسه إتجاه مايقوم به من بيع وشراء وإتفاق وأعطاء معلومات موقعه
التعليقات المنشورة لا تعبر عن رأي موقع القرية الالكترونية ولايتحمل الموقع أي مسؤولية قانونية حيال ذلك (ويتحمل كاتبها مسؤولية النشر)

Powered by vBulletin® Version 3.8.6, Copyright ©2000 - 2025