Hey Champs,
Today we Will see how to use Ultrasonic sensors(HC-SR04) for Obstacle Detection And its interfacing with AVR Atmega16.
HC-SR04:-
level time with the following formula,
Echo pulse (uS) / 58 = Distance in centimeters
Echo pulse (uS) / 148 = Distance in inch
Distance = (high level time×velocity of sound (i.e. 340M/S) / 2).
Timing Diagram
Ultrasonic sending trigger and
reading Echo
2. Sonar automatically sends eight 40kHz inpulses
3. Sonar rises high on Echo output and then after some time drops
output to low .
4. Based on output time difference deltaT = lowT-highT calculate:
distance = [ deltaT * sound_speed(340m/s) ] / 2
5. Make a delay before starting the next cycle to compensate for late echoes
#include<avr/wdt.h>
#include<avr/interrupt.h>
#include<util/delay.h>
volatile long avg = 0;
volatile unsigned char up = 0;
volatile uint32_t running = 0;
volatile uint32_t timercounter =0;
int turn = 0;
{
if (up) {
timercounter++;
}
}
void light_flashing()
{
PORTA = 0x00;
if ((avg>0) && (avg <= 15))
{
PORTB = 0b00000110; // Moving of bot backward
PORTA = 0b10000000;// For buzzer
turn = 1;
}
else if ((avg > 15) && (avg <= 30))
{
if (turn == 1){
PORTB = 0b1110101;// Turning of Bot right
_delay_ms(50);
turn = 0;
}else{
PORTB = 0b11111001;
PORTA = 0x00;
}
}
else if ((avg > 30) && (avg <= 45))
{
PORTB = 0b11101001;
PORTA = 0x00;
}
else if ((avg > 45) && (avg <= 60))
{
PORTB = 0b11001001;
PORTA = 0x00;
}
else if ((avg > 60) && (avg <= 75))
{
PORTB = 0b10001001;
PORTA = 0x00;
}
else if (avg > 75)
{
PORTB = 0b10001001;
}
}
SIGNAL(INT1_vect){
if(running){ //accept interrupts only when sonar was started
if (up == 0) { // voltage rise, start time measurement
up = 1;
timercounter = 0;
TCCR0 |= (0 << CS02)|(0 << CS01)|(1 << CS00); // Start/initialize timer with prescalar 0
TCNT0 = 0; // Initialize Counter
} else { // voltage drop, stop time measurement
up = 0;
avg = (timercounter*256+TCNT0)/58;// divide by 58 to get distance in cm
light_flashing();
running = 0;
}
}
}
//send signal for trigger the ultrasonic for 10uS
void send_trigger()
{
PORTD = 0x00;
_delay_us(5);
PORTD = 0xf0;
running = 1;
_delay_us(10);
PORTD = 0x00;
}
int main()
{
DDRD = 0xf0;//pin d3 is used as input and pin d6 as output for trigger
PORTD = 0x00;
DDRB = 0xff;
PORTB = 0x00;
DDRA = 0xff;
PORTA = 0x00;
MCUCR |= (0 << ISC11) | (1 << ISC10); // enable interrupt on any(rising/droping) edge
GICR |= (1 << INT1); //Turns on INT1
TIMSK |= (1 << TOIE0); // enable timer interrupt
sei(); // enable all(global) interrupts
while(1)
{
if(running == 0) {
_delay_ms(60);
send_trigger();
}
}
}
Today we Will see how to use Ultrasonic sensors(HC-SR04) for Obstacle Detection And its interfacing with AVR Atmega16.
HC-SR04:-
The HC-SR04 Ultrasonic Range Finder is one of the most popular distance sensors among robotic hobbyists. Ultrasonic Sensor (HC SR-04) module is low cost, high performance sensor and provides stable and high ranging accuracy. It's ranging distance is 2cm to 350cm with 3mm accuracy. The module includes ultrasonic transmitter, receiver and control circuit.The module is relatively inexpensive, accurate, and easy to interface
with a micro-controller. The HC-SR04 range makes it ideally suited for developing object detection and
avoidance schemes for small and medium size robots. As with any sensor,
in order to make best use of its capabilities it is essential to have a
clear understanding of the nature of the device
HC-SR04
Working:-
Sensor works on trigger (TTL-10usec) pulse provided by any device. When trigger pulse sends to the
trigger pin of sensor. Then sensor module will send the 8 cycle of 40KHz ultrasonic pulses and receives echo signal after striking on object & reflect back. Which is detailed in a below shown Timing Diagram. The distance between the sensor and the object is calculated by measuring high level time of the Echo pulse which can be retrieved from ECHO pin of the sensor module and processing the highlevel time with the following formula,
Echo pulse (uS) / 58 = Distance in centimeters
Echo pulse (uS) / 148 = Distance in inch
Distance = (high level time×velocity of sound (i.e. 340M/S) / 2).
reading Echo
Ultrasonic sensor interfacing:-
1. Send high impulse to Trig input for minimum 10us2. Sonar automatically sends eight 40kHz inpulses
3. Sonar rises high on Echo output and then after some time drops
output to low .
4. Based on output time difference deltaT = lowT-highT calculate:
distance = [ deltaT * sound_speed(340m/s) ] / 2
5. Make a delay before starting the next cycle to compensate for late echoes
Connection:-
Vcc = +5v
Trig = PD6
Echo = PD3
Ground = 0v
CODE:-
#define F_CPU 8000000UL
#include <avr/io.h>#include<avr/wdt.h>
#include<avr/interrupt.h>
#include<util/delay.h>
volatile long avg = 0;
volatile unsigned char up = 0;
volatile uint32_t running = 0;
volatile uint32_t timercounter =0;
int turn = 0;
// interrupt for INT1 pin, to detect high/low voltage changes
ISR(TIMER0_OVF_vect){
if (up) {
timercounter++;
}
}
void light_flashing()
{
PORTA = 0x00;
if ((avg>0) && (avg <= 15))
{
PORTB = 0b00000110; // Moving of bot backward
PORTA = 0b10000000;// For buzzer
turn = 1;
}
else if ((avg > 15) && (avg <= 30))
{
if (turn == 1){
PORTB = 0b1110101;// Turning of Bot right
_delay_ms(50);
turn = 0;
}else{
PORTB = 0b11111001;
PORTA = 0x00;
}
}
else if ((avg > 30) && (avg <= 45))
{
PORTB = 0b11101001;
PORTA = 0x00;
}
else if ((avg > 45) && (avg <= 60))
{
PORTB = 0b11001001;
PORTA = 0x00;
}
else if ((avg > 60) && (avg <= 75))
{
PORTB = 0b10001001;
PORTA = 0x00;
}
else if (avg > 75)
{
PORTB = 0b10001001;
}
}
// We assume, that high voltage rise comes before low drop and not vice versa
// Check change in the level at the PD3 for falling/rising edgeSIGNAL(INT1_vect){
if(running){ //accept interrupts only when sonar was started
if (up == 0) { // voltage rise, start time measurement
up = 1;
timercounter = 0;
TCCR0 |= (0 << CS02)|(0 << CS01)|(1 << CS00); // Start/initialize timer with prescalar 0
TCNT0 = 0; // Initialize Counter
} else { // voltage drop, stop time measurement
up = 0;
avg = (timercounter*256+TCNT0)/58;// divide by 58 to get distance in cm
light_flashing();
running = 0;
}
}
}
//send signal for trigger the ultrasonic for 10uS
void send_trigger()
{
PORTD = 0x00;
_delay_us(5);
PORTD = 0xf0;
running = 1;
_delay_us(10);
PORTD = 0x00;
}
int main()
{
DDRD = 0xf0;//pin d3 is used as input and pin d6 as output for trigger
PORTD = 0x00;
DDRB = 0xff;
PORTB = 0x00;
DDRA = 0xff;
PORTA = 0x00;
MCUCR |= (0 << ISC11) | (1 << ISC10); // enable interrupt on any(rising/droping) edge
GICR |= (1 << INT1); //Turns on INT1
TIMSK |= (1 << TOIE0); // enable timer interrupt
sei(); // enable all(global) interrupts
while(1)
{
if(running == 0) {
_delay_ms(60);
send_trigger();
}
}
}
Thanx!
For any Problem in Code plz. Ask me. :)
No comments:
Post a Comment