====================================================
An Automated Motion-Sensing Door Control System using Arduino Uno, PIR sensor, and motor driver for hands-free door operation. Detects human presence through infrared motion sensing and automatically opens/closes doors for enhanced convenience and hygiene in commercial and residential applications.
- Motion Detection - PIR sensor for detecting human presence and movement
- Automatic Operation - Hands-free door opening and closing mechanism
- LCD Status Display - Real-time system status and movement detection feedback
- Motor Control - L293D driver for bidirectional door motor operation
- Adjustable Sensitivity - Configurable PIR sensor range and timing
- Energy Efficient - Low power consumption with standby mode
- Hygienic Solution - No-touch operation for improved cleanliness
- Commercial Grade - Suitable for malls, offices, and public buildings
- DIY Friendly - Easy assembly with readily available components
- Arduino Uno (1x) - Main microcontroller board
- PIR Motion Sensor (1x) - Passive infrared motion detection
- 16x2 LCD Display (1x) - Status display module
- L293D Motor Driver IC (1x) - Motor control and direction switching
- DC Motor (1x) - Door mechanism (or CD/DVD tray motor)
- 1kฮฉ Resistor (1x) - Pull-up resistor for PIR sensor
- Breadboard - For circuit assembly
- Jumper Wires - Male-to-male and male-to-female connections
- 9V Battery - For portable operation
- USB Power - For development and testing
- DC Adapter (7-12V) - For permanent installation
- 10kฮฉ Potentiometer - LCD contrast adjustment
- LED Indicators - Status feedback lights
- Buzzer - Audio alerts for door operation
- Limit Switches - Door position feedback
- Relay Module - For high-power motor control
PIR Sensor Connections:
โโโโโโโโโโโโโโโโโโโฌโโโโโโโโโโโโโโโโโโโฌโโโโโโโโโโโโโโโโโโโโโโ
โ PIR Sensor Pin โ Arduino Pin โ Function โ
โโโโโโโโโโโโโโโโโโโผโโโโโโโโโโโโโโโโโโโผโโโโโโโโโโโโโโโโโโโโโโค
โ VCC โ 5V โ Power Supply โ
โ GND โ GND โ Ground โ
โ OUT (Dout) โ A0 (Pin 14) โ Motion Detection โ
โโโโโโโโโโโโโโโโโโโดโโโโโโโโโโโโโโโโโโโดโโโโโโโโโโโโโโโโโโโโโโ
16x2 LCD Display Connections:
โโโโโโโโโโโโโโโโโโโฌโโโโโโโโโโโโโโโโโโโฌโโโโโโโโโโโโโโโโโโโโโโ
โ LCD Pin โ Arduino Pin โ Function โ
โโโโโโโโโโโโโโโโโโโผโโโโโโโโโโโโโโโโโโโผโโโโโโโโโโโโโโโโโโโโโโค
โ VSS โ GND โ Ground โ
โ VDD โ 5V โ Power Supply โ
โ V0 โ 10kฮฉ Pot โ Contrast Control โ
โ RS โ D13 โ Register Select โ
โ EN โ D12 โ Enable โ
โ D4 โ D11 โ Data Bit 4 โ
โ D5 โ D10 โ Data Bit 5 โ
โ D6 โ D9 โ Data Bit 6 โ
โ D7 โ D8 โ Data Bit 7 โ
โ A โ 5V โ Backlight Anode โ
โ K โ GND โ Backlight Cathode โ
โ RW โ GND โ Read/Write (Ground) โ
โโโโโโโโโโโโโโโโโโโดโโโโโโโโโโโโโโโโโโโดโโโโโโโโโโโโโโโโโโโโโโ
L293D Motor Driver Connections:
โโโโโโโโโโโโโโโโโโโฌโโโโโโโโโโโโโโโโโโโฌโโโโโโโโโโโโโโโโโโโโโโ
โ L293D Pin โ Arduino Pin โ Function โ
โโโโโโโโโโโโโโโโโโโผโโโโโโโโโโโโโโโโโโโผโโโโโโโโโโโโโโโโโโโโโโค
โ IN1 โ D0 โ Motor Control 1 โ
โ IN2 โ D1 โ Motor Control 2 โ
โ OUT1 โ Motor Wire 1 โ Motor Output 1 โ
โ OUT2 โ Motor Wire 2 โ Motor Output 2 โ
โ VCC1 โ 5V โ Logic Power โ
โ VCC2 โ 9V โ Motor Power โ
โ GND โ GND โ Common Ground โ
โ EN1 โ 5V โ Enable Pin โ
โโโโโโโโโโโโโโโโโโโดโโโโโโโโโโโโโโโโโโโดโโโโโโโโโโโโโโโโโโโโโโ
System Operation Flow:
โโโโโโโโโโโโโโโโโโโฌโโโโโโโโโโโโโโโโโโโฌโโโโโโโโโโโโโโโโโโโโโโ
โ Input Stage โ Processing โ Output Stage โ
โโโโโโโโโโโโโโโโโโโผโโโโโโโโโโโโโโโโโโโผโโโโโโโโโโโโโโโโโโโโโโค
โ PIR Sensor โ Arduino Uno โ Motor Control โ
โ Motion Detectionโ Logic Processing โ Door Open/Close โ
โ Infrared Sensingโ Timer Control โ LCD Status Display โ
โ Human Presence โ State Machine โ Visual Feedback โ
โโโโโโโโโโโโโโโโโโโดโโโโโโโโโโโโโโโโโโโดโโโโโโโโโโโโโโโโโโโโโโ
Download and install Arduino IDE from arduino.cc
Install required library via Library Manager:
// Required Libraries
#include <LiquidCrystal.h> // LCD display control (pre-installed)
// No additional libraries needed for basic functionality
-
PIR Sensor Connection:
- VCC โ Arduino 5V
- GND โ Arduino GND
- OUT โ Arduino A0 (analog pin 14)
-
LCD Display Setup:
- Connect power (VDD to 5V, VSS to GND)
- Connect control pins (RS to D13, EN to D12)
- Connect data pins (D4-D7 to Arduino D11-D8)
- RW pin to GND for write mode only
-
Motor Driver (L293D):
- IN1 โ Arduino D0
- IN2 โ Arduino D1
- Motor connections to OUT1 and OUT2
- Power supply: VCC1 to 5V, VCC2 to motor voltage
-
Power Distribution:
- Connect 9V battery or DC adapter to Arduino Vin pin
- Ensure common ground for all components
git clone https://github.com/Circuit-Digest/Arduino-Automatic-Door.git
cd Arduino-Automatic-Door
Open automatic_door_opener.ino
in Arduino IDE and upload to your board.
#include <LiquidCrystal.h>
// Initialize LCD with interface pins
LiquidCrystal lcd(13, 12, 11, 10, 9, 8);
// Pin definitions
#define PIR_sensor 14 // Analog pin A0
#define m11 0 // Motor control pin 1
#define m12 1 // Motor control pin 2
void setup() {
lcd.begin(16, 2);
pinMode(m11, OUTPUT);
pinMode(m12, OUTPUT);
pinMode(PIR_sensor, INPUT);
// Display startup message
lcd.print(" Automatic ");
lcd.setCursor(0, 1);
lcd.print(" Door Opener ");
delay(3000);
lcd.clear();
}
void loop() {
if (digitalRead(PIR_sensor)) {
// Motion detected - open door sequence
lcd.setCursor(0, 0);
lcd.print("Movement Detected");
lcd.setCursor(0, 1);
lcd.print(" Gate Opened ");
// Open door
digitalWrite(m11, HIGH);
digitalWrite(m12, LOW);
delay(1000);
// Stop motor
digitalWrite(m11, LOW);
digitalWrite(m12, LOW);
delay(1000);
// Close door
lcd.clear();
lcd.print(" Gate Closed ");
digitalWrite(m11, LOW);
digitalWrite(m12, HIGH);
delay(1000);
// Stop motor
digitalWrite(m11, LOW);
digitalWrite(m12, LOW);
delay(1000);
} else {
// No motion - door closed state
lcd.setCursor(0, 0);
lcd.print(" No Movement ");
lcd.setCursor(0, 1);
lcd.print(" Gate Closed ");
digitalWrite(m11, LOW);
digitalWrite(m12, LOW);
}
}
// Enhanced version with adjustable timing and states
enum DoorState {
CLOSED,
OPENING,
OPEN,
CLOSING
};
DoorState currentState = CLOSED;
unsigned long stateStartTime = 0;
const unsigned long DOOR_OPEN_TIME = 3000; // 3 seconds
const unsigned long DOOR_MOVE_TIME = 1000; // 1 second to open/close
void loop() {
bool motionDetected = digitalRead(PIR_sensor);
unsigned long currentTime = millis();
switch (currentState) {
case CLOSED:
if (motionDetected) {
startDoorOpening();
currentState = OPENING;
stateStartTime = currentTime;
}
break;
case OPENING:
if (currentTime - stateStartTime >= DOOR_MOVE_TIME) {
stopMotor();
currentState = OPEN;
stateStartTime = currentTime;
updateDisplay(" Door Open ", " Please Enter ");
}
break;
case OPEN:
if (currentTime - stateStartTime >= DOOR_OPEN_TIME) {
startDoorClosing();
currentState = CLOSING;
stateStartTime = currentTime;
}
break;
case CLOSING:
if (currentTime - stateStartTime >= DOOR_MOVE_TIME) {
stopMotor();
currentState = CLOSED;
updateDisplay(" Door Closed ", " System Ready ");
}
break;
}
}
void startDoorOpening() {
digitalWrite(m11, HIGH);
digitalWrite(m12, LOW);
updateDisplay("Movement Detected", " Door Opening ");
}
void startDoorClosing() {
digitalWrite(m11, LOW);
digitalWrite(m12, HIGH);
updateDisplay(" Time Expired ", " Door Closing ");
}
void stopMotor() {
digitalWrite(m11, LOW);
digitalWrite(m12, LOW);
}
void updateDisplay(String line1, String line2) {
lcd.clear();
lcd.setCursor(0, 0);
lcd.print(line1);
lcd.setCursor(0, 1);
lcd.print(line2);
}
// Support for multiple PIR sensors (both sides of door)
#define PIR_sensor_1 14 // Inside sensor
#define PIR_sensor_2 15 // Outside sensor
void loop() {
bool motion1 = digitalRead(PIR_sensor_1);
bool motion2 = digitalRead(PIR_sensor_2);
if (motion1 || motion2) {
String direction = motion1 ? "Inside" : "Outside";
lcd.setCursor(0, 0);
lcd.print("Motion: " + direction);
// Open door regardless of direction
openDoor();
} else {
// No motion from either sensor
closeDoor();
}
}
Arduino-Automatic-Door/
โโโ Arduino_Code/
โ โโโ automatic_door_opener.ino # Main door control program
โ โโโ pir_sensor_test.ino # PIR sensor testing
โ โโโ motor_driver_test.ino # L293D motor testing
โ โโโ lcd_display_test.ino # LCD display testing
โ โโโ enhanced_door_control.ino # Advanced door control
โโโ Circuit_Diagrams/
โ โโโ Complete_Circuit.png # Full circuit schematic
โ โโโ Breadboard_Layout.png # Breadboard assembly
โ โโโ PCB_Design.png # PCB layout (optional)
โ โโโ Motor_Connections.png # Motor wiring details
โโโ Documentation/
โ โโโ Component_Guide.md # Component specifications
โ โโโ Assembly_Instructions.md # Step-by-step assembly
โ โโโ Troubleshooting.md # Common issues & solutions
โ โโโ Installation_Guide.md # Mounting and setup
โโโ 3D_Models/
โ โโโ door_mechanism.stl # 3D printable door parts
โ โโโ sensor_housing.stl # PIR sensor enclosure
โ โโโ control_box.stl # Electronics enclosure
โโโ Examples/
โ โโโ ultrasonic_version.ino # Using ultrasonic sensor
โ โโโ servo_motor_control.ino # Servo motor version
โ โโโ bluetooth_control.ino # Remote control version
โโโ README.md
PIR Sensor Always High
- Check PIR sensor sensitivity potentiometer adjustment
- Ensure proper warm-up time (30-60 seconds after power on)
- Verify 5V power supply to sensor
- Keep sensor away from heat sources and direct sunlight
Motor Not Responding
- Verify L293D motor driver connections
- Check motor power supply (separate from Arduino if high current)
- Test motor directly with battery
- Ensure enable pins on L293D are HIGH
LCD Display Not Working
- Check power connections (VDD to 5V, VSS to GND)
- Adjust contrast using potentiometer on V0 pin
- Verify data pin connections (D4-D7)
- Test with simple "Hello World" LCD sketch
Door Opens But Doesn't Close
- Check motor driver IN1 and IN2 connections
- Verify motor can rotate in both directions
- Adjust timing delays in code
- Ensure adequate power supply for motor operation
// PIR sensor calibration and testing
void calibratePIR() {
Serial.begin(9600);
pinMode(PIR_sensor, INPUT);
Serial.println("PIR Sensor Calibration");
Serial.println("Warming up for 30 seconds...");
for (int i = 30; i > 0; i--) {
Serial.print(i);
Serial.println(" seconds remaining");
delay(1000);
}
Serial.println("Calibration complete. Testing sensor...");
while (true) {
if (digitalRead(PIR_sensor)) {
Serial.println("Motion detected!");
delay(1000);
} else {
Serial.println("No motion");
delay(500);
}
}
}
// Test motor rotation in both directions
void testMotor() {
Serial.println("Testing motor clockwise...");
digitalWrite(m11, HIGH);
digitalWrite(m12, LOW);
delay(2000);
Serial.println("Motor stop...");
digitalWrite(m11, LOW);
digitalWrite(m12, LOW);
delay(1000);
Serial.println("Testing motor counter-clockwise...");
digitalWrite(m11, LOW);
digitalWrite(m12, HIGH);
delay(2000);
Serial.println("Motor stop...");
digitalWrite(m11, LOW);
digitalWrite(m12, LOW);
delay(1000);
}
- Shopping Malls - Automatic entrance and exit doors
- Office Buildings - Hands-free access to meeting rooms and restrooms
- Hospitals - Hygienic door operation in sterile environments
- Hotels - Guest room and lobby door automation
- Residential - Smart home entrance door control
- Warehouses - Automated loading dock doors
- Public Transport - Bus and train door automation
- Accessibility - Assistance for wheelchair users and elderly
- Smartphone Control - Bluetooth/WiFi app for remote operation
- Security Integration - RFID/keypad access control
- Multiple Sensors - Ultrasonic, laser, or camera-based detection
- Voice Control - Voice command integration
- IoT Connectivity - Cloud monitoring and control
- Energy Harvesting - Solar power for remote installations
- Machine Learning - Adaptive behavior based on usage patterns
- Safety Features - Obstacle detection and emergency stop
Component | Specification |
---|---|
PIR Sensor | |
Detection Range | 3-7 meters (adjustable) |
Detection Angle | 120 degrees |
Operating Voltage | 5V DC |
Current Consumption | <50ยตA |
Response Time | 0.3-25 seconds |
L293D Motor Driver | |
Operating Voltage | 4.5V to 36V |
Output Current | 600mA per channel |
Peak Current | 1.2A per channel |
Logic Supply | 5V |
System Performance | |
Detection Distance | Up to 7 meters |
Door Operation Time | 1-3 seconds |
Power Consumption | 200-500mA (active) |
Operating Temperature | 0ยฐC to 50ยฐC |
PIR (Passive Infrared) sensors detect changes in infrared radiation:
- Pyroelectric Detection - Detects infrared energy from warm objects
- Fresnel Lens Array - Focuses infrared radiation onto sensor elements
- Differential Detection - Compares signals from two sensor halves
- BISS0001 IC - Processes signals and provides digital output
// Enhanced motion detection with noise filtering
class PIRSensor {
private:
int pin;
unsigned long lastDetection;
unsigned long debounceTime;
bool currentState;
public:
PIRSensor(int sensorPin, unsigned long debounce = 500) {
pin = sensorPin;
debounceTime = debounce;
currentState = false;
lastDetection = 0;
pinMode(pin, INPUT);
}
bool motionDetected() {
bool reading = digitalRead(pin);
unsigned long currentTime = millis();
if (reading && !currentState) {
if (currentTime - lastDetection > debounceTime) {
currentState = true;
lastDetection = currentTime;
return true;
}
} else if (!reading) {
currentState = false;
}
return false;
}
bool isActive() {
return currentState;
}
};
Most PIR sensors have two potentiometers:
- Sensitivity (Sx) - Detection range adjustment
- Time Delay (Tx) - Output duration after detection
- ๐ Complete Tutorial: Automatic Door Opener Project using Arduino
- ๐ PIR Sensor Guide: PIR Motion Detector Sensor Circuit
- ๐ Home Automation: Arduino Home Automation Projects
- ๐ Motor Control: Arduino Motor Control Projects
- ๐ฑ LCD Projects: Arduino LCD Interfacing Tutorials
Distance (m) | Detection Rate | False Positives |
---|---|---|
1-2 | 99% | <1% |
2-4 | 95% | <2% |
4-6 | 90% | <3% |
6-7 | 85% | <5% |
Mode | Current Draw | Power (5V) | Battery Life (2000mAh) |
---|---|---|---|
Standby | 50mA | 250mW | 40 hours |
Door Opening | 300mA | 1.5W | 6.7 hours |
Door Closing | 300mA | 1.5W | 6.7 hours |
Display Only | 80mA | 400mW | 25 hours |
- PIR Detection: 0.3-3 seconds (adjustable)
- Arduino Processing: <10ms
- Motor Start: 50-100ms
- Door Movement: 1-3 seconds
- Total Response: 2-7 seconds
- Use proper fusing for motor circuits
- Ensure adequate ventilation for L293D motor driver
- Implement emergency stop mechanisms
- Use appropriate wire gauges for current requirements
// Safety features implementation
class SafetySystem {
private:
int obstacleSensor;
int emergencyStop;
public:
bool checkSafety() {
// Check for obstacles in door path
if (digitalRead(obstacleSensor)) {
stopDoorImmediately();
return false;
}
// Check emergency stop button
if (digitalRead(emergencyStop)) {
stopDoorImmediately();
return false;
}
return true;
}
void stopDoorImmediately() {
digitalWrite(m11, LOW);
digitalWrite(m12, LOW);
displayEmergencyMessage();
}
};
- Mount PIR sensor at appropriate height (2.2-2.5m)
- Ensure clear detection zone without obstacles
- Secure all electrical connections
- Provide manual override mechanism
- Install warning signs for automatic door operation
// Power saving techniques
void enterSleepMode() {
// Put Arduino in sleep mode between detections
set_sleep_mode(SLEEP_MODE_PWR_DOWN);
sleep_enable();
sleep_mode();
sleep_disable();
}
// Optimized loop with power management
void loop() {
if (digitalRead(PIR_sensor)) {
// Active mode - normal operation
processDoorControl();
} else {
// Standby mode - reduce power
delay(100); // Longer delay when no motion
}
}
// Non-blocking door control
unsigned long lastMotionTime = 0;
bool doorOpening = false;
bool doorClosing = false;
void loop() {
unsigned long currentTime = millis();
if (digitalRead(PIR_sensor)) {
lastMotionTime = currentTime;
if (!doorOpening && currentState == CLOSED) {
startDoorOpening();
}
}
// Non-blocking state management
updateDoorState(currentTime);
}
If you find this project helpful:
- โญ Star this repository
- ๐ด Fork and contribute improvements
- ๐ Report bugs and issues
- ๐ Share your automatic door implementations
- Fork the repository
- Create feature branch (
git checkout -b feature/improvement
) - Commit changes (
git commit -am 'Add new feature'
) - Push to branch (
git push origin feature/improvement
) - Create Pull Request
Built with โค๏ธ by Circuit Digest
Advancing automation for a more convenient world
automatic door opener
arduino pir sensor
motion detection door
l293d motor driver
arduino automation
smart door control
pir motion sensor
arduino motor control
automated entrance
hands-free door
commercial door automation
arduino lcd projects