Engineers Garage

  • Electronic Projects & Tutorials
    • Electronic Projects
      • Arduino Projects
      • AVR
      • Raspberry pi
      • ESP8266
      • BeagleBone
      • 8051 Microcontroller
      • ARM
      • PIC Microcontroller
      • STM32
    • Tutorials
      • Audio Electronics
      • Battery Management
      • Brainwave
      • Electric Vehicles
      • EMI/EMC/RFI
      • Hardware Filters
      • IoT tutorials
      • Power Tutorials
      • Python
      • Sensors
      • USB
      • VHDL
    • Circuit Design
    • Project Videos
    • Components
  • Articles
    • Tech Articles
    • Insight
    • Invention Stories
    • How to
    • What Is
  • News
    • Electronic Product News
    • Business News
    • Company/Start-up News
    • DIY Reviews
    • Guest Post
  • Forums
    • EDABoard.com
    • Electro-Tech-Online
    • EG Forum Archive
  • DigiKey Store
    • Cables, Wires
    • Connectors, Interconnect
    • Discrete
    • Electromechanical
    • Embedded Computers
    • Enclosures, Hardware, Office
    • Integrated Circuits (ICs)
    • Isolators
    • LED/Optoelectronics
    • Passive
    • Power, Circuit Protection
    • Programmers
    • RF, Wireless
    • Semiconductors
    • Sensors, Transducers
    • Test Products
    • Tools
  • Learn
    • eBooks/Tech Tips
    • Design Guides
    • Learning Center
    • Tech Toolboxes
    • Webinars & Digital Events
  • Resources
    • Digital Issues
    • EE Training Days
    • LEAP Awards
    • Podcasts
    • Webinars / Digital Events
    • White Papers
    • Engineering Diversity & Inclusion
    • DesignFast
  • Guest Post Guidelines
  • Advertise
  • Subscribe

KEYPAD CONTROLLED WIRELESS ROBOT

By HIMANSHU SAINI April 21, 2008

INTRODUCTION:
 
Keypads are parts of HMI or Human Machine Interface and play really important role in a small embedded system where human interaction or human input is needed. Matrix keypads are well known for their simple architecture and ease of interfacing. So in this project, keypad is used to control the direction of robot. Here, we will use the 4X3 keypad as the input device and the 433MHz RF circuit to drive the robot wirelessly in different direction. Also, we will display the direction of movement of the robot in a 16X2 alphanumeric LCD.
 
Keypad Controlled Wireless Robot Setup
 
Keypad Controlled Wireless Robot
 
COMPONENTS REQUIRED:
 

@page { margin: 2cm }
p { margin-bottom: 0.25cm; direction: ltr; line-height: 120%; text-align: left; orphans: 2; widows: 2 }
a:link { color: #0000ff }

COMPONENT

QUANTITY

ATmega32 Microcontroller IC

1

4×3 Keypad Module

1

RF transmitter and Receiver module

1

HT12E Encoder IC

1

HT12D Decoder IC

1

L293D motor driver IC

1

7805 and 7812 voltage regulator IC

1

Battery-12V

2

Geared DC motor

2

 

BLOCK DIAGRAM:
TRANSMITTER:
 
Keypad Controlled wireless Robot transmitter block diagram
Keypad Controlled wireless Robot transmitter block diagram
 
 
RECEIVER:
 
Keypad Controlled wireless Robot receiver block diagram
Keypad Controlled wireless Robot receiver block diagram
 
 
PROJECT DESCRIPTION:
 
In this project, in order to design a keypad controlled wireless controlled robot, AVR ATmega32 microcontroller is used. In our case, we will be using keypad module to control the movement of robot by giving input through pressing a specific key in keypad. Then we will be using a RF transmitter and Receiver to control the robot wirelessly. Where the RF transmitter is attached to controller output along with encoder IC HT12E. RF receiver is mounted on the robot to receive the data signal from the transmitter and decode it using the decoder IC and control signal is given to motor driver to run the robot.
 
CIRCUIT CONNECTION:
 
TRANSMITTER SECTION
 
 
Keypad Controlled wireless Robot Transmitter Setup
 
KEYPAD:
 
In this project, we will be using Keypad to control the movement of robot by pressing the specific number on number. This keypad contains 12 buttons with three columns and 4 rows. In the keypad 4-wire is used as ROWS and three wires are used as COLUMS. Wire number can be count from the left hand side to the right hand side.
 

@page { margin: 2cm }
p { margin-bottom: 0.25cm; direction: ltr; line-height: 120%; text-align: left; orphans: 2; widows: 2 }
a:link { color: #0000ff }

@page { margin: 2cm }
p { margin-bottom: 0.25cm; direction: ltr; line-height: 120%; text-align: left; orphans: 2; widows: 2 }
a:link { color: #0000ff }

KEYPAD PIN

ARDUINO MEGA PIN.NO

R1

PA0

R2

PA1

R3

PA2

R4

PA3

C1

PA4

C2

PA5

C3

PA6

 
ATMEGA 32:
 
The circuit is built around AVR Atmega32. There are distinct circuit sections that are interfaced to the Atmega32 to realize the project functioning. In the project, where Atmel AVR ATmega32 is a low-power CMOS 8-bit microcontroller based on the AVR enhanced RISC architecture. By executing powerful instructions in a single clock cycle, the ATmega32 achieves throughputs approaching 1 MIPS per MHz allowing the system designed to optimize power consumption versus processing speed.
 
LCD MODULE:
 
  The LCD display is used to display the direction of the robot. When the project is powered ON, it first flashes initial messages showing the intent of the project. Once the Atmega32 sketch initializes the circuit, direction of robot are displayed on the LCD screen. The 16X2 LCD display is connected to the Atmega32 IC by connecting its data pins to pins 1 to 8 of port-B of the Atmega32 IC. The RS, R/W and E pins of the LCD are connected to pins 0 to 2 of port-D of the Atmega32 IC respectively. To know more about interfacing LCD with Atmega32 refer tutorial How to display text on 16×2 LCD using AVR microcontroller (ATmega16/ATmega32).
 

@page { margin: 2cm }
p { margin-bottom: 0.25cm; direction: ltr; line-height: 120%; text-align: left; orphans: 2; widows: 2 }
a:link { color: #0000ff }

 

LCD DISPLAY

 

ATMEGA32 IC

D0 To D7 PIN

PIN 1 To 8 of PORTB

RS

PIN 0 of PORTD

RW

PIN 1 of PORTD

EN

PIN 2 of PORTD

 
 
POWER SUPPLY:
 
In the circuit, Transmitter Module, ATmega32, LCD Module and the HT12E need a 5V regulated DC regulated supply for its operation. The DC power supply is used as major power supply. The output from power supply is regulated to 5V using 7805. The pin 1 of the voltage regulator ICs is connected to the anode of the power supply and pin 2 of ICs is connected to ground. The respective voltage outputs are drawn from pin 3 of the voltage regulator ICs. A LED along with a 1KΩ pull-up resistor is also connected between common ground and output pin to get a visual hint of supply continuity.  
 
 
HT12E ENCODER AND RF TRANSMITTER:
 
HT12E is an encoder integrated circuit of 212 series of encoders. They are paired with 212 series of decoders for use in remote control system applications. 
Simply put, HT12E converts the parallel inputs into serial output. It encodes the 12 bit parallel data into serial for transmission through an RF transmitter. These 12 bits are divided into 8 address bits and 4 data bits.
 
 HT12E has a transmission enable pin which is active low. When a trigger signal is received on TE pin, the programmed addresses/data are transmitted together with the header bits via an RF or an infrared transmission medium. HT12E begins a 4-word transmission cycle upon receipt of a transmission enable. This cycle is repeated as long as TE is kept low. As soon as TE returns to high, the encoder output completes its final cycle and then stops.
 
In this project the output from the microcontroller pin PC0, PC1, PC2 and PC3 of PORTC are connected to the 10th, 11th, 13th, 14th pin of the encoder IC respectively with pull down resistor of 1KΩ.
 
The RF module, as the name suggests, operates at Radio Frequency. The corresponding frequency range varies between 30 kHz & 300 GHz. In this RF system, the digital data is represented as variations in the amplitude of carrier wave. This kind of modulation is known as Amplitude Shift Keying (ASK). Refer RF Module (Transmitter & Receiver). In order to make a transmission the transmitter modules takes the input to serial data pin where the data is given from the output pin 17th of the encoder IC.
 
RECEIVER SECTION
 
Keypad Controlled wireless Robot Receiver Setup
 
Keypad Controlled wireless Robot Receiver Setup
 
 
POWER SUPPLY:
 
In the circuit, Receiver Module, Motor Driver IC supply and the HT12D need a 5V regulated DC while DC motor needs 12V regulated DC for its operation. The 12V NIMH battery is used as major power supply. The output from battery is regulated to 5V and 12V using 7805 and 7812 ICs. The pin 1 of both the voltage regulator ICs is connected to the anode of the battery and pin 2 of both ICs is connected to ground. The respective voltage outputs are drawn from pin 3 of the respective voltage regulator ICs. A LED along with a 1KΩ pull-up resistor is also connected between common ground and output pin to get a visual hint of supply continuity.  
 
RF RECEIVER AND HT12D DECODER:
 
The receiver receives the wireless serial data transmitted by the transmitter with same address as the receiver has and it gives the received data to the Decoder IC HT12D of 16th pin. HT12D is a decoder integrated circuit that belongs to 212 series of decoders. This series of decoders are mainly used for remote control system applications, like burglar alarm, car door controller, security system etc. It is mainly provided to interface RF and infrared circuits.  They are paired with 212 series of encoders. The chosen pair of encoder/decoder should have same number of addresses and data format.
 
In simple terms, HT12D converts the serial input into parallel outputs. It decodes the serial addresses and data received by, say, an RF receiver, into parallel data and sends them to output data pins. The serial input data is compared with the local addresses three times continuously. The input data code is decoded when no error or unmatched codes are found. A valid transmission in indicated by a high signal at VT pin.
 
HT12D is capable of decoding 12 bits, of which 8 are address bits and 4 are data bits. The data on 4 bit latch type output pins remain unchanged until new is received.
Then the decoded data is given to input to the L293D IC.
 
L293D MOTOR DRIVER:
 
L293D is a dual H-bridge motor driver integrated circuit (IC). Motor drivers act as current amplifiers since they take a low-current control signal and provide a higher-current signal. This higher current signal is used to drive the motors. For to know about IC function, pin description and datasheet refer L293D. In this project the HT12D data output pin 10th and 11th is connected to the Input A 2nd and 7th pin of L293 D respectively and the HT12D data output pin 12th an 13th is connected to the input B 10th and 15th of L293 D IC respectively. Enable pin of L293D is supplied with 5V and the 4, 5, 12, 13 pins are connected to ground. 8th pin of L293D IC is supplied with 12V for motor power.
 
GEARED DC MOTOR:
 
The 12V DC Geared Motor can be used in variety of robotics applications and is available with wide range of RPM and Torque, which allow your robot to move based on the control signal it receives from the motor driver IC. Two geared DC motors are used to run the robot. Left motor positive and negative is connected to output A side pin 3rd and 6th of L293D IC and right motor positive and negative is connected to output B pin 11th and 14th of L293D IC respectively. 
 
CIRCUIT WORKING:
 
Make the circuit connections according to the circuit diagram and explanation given above. The ATmega32 microcontroller will read the 4X3 keypad output. After reading the 4X3 keypad output, the ATmega32 microcontroller will process the keypad output value to find pressed key value. According to the pressed key value, the ATmega32 microcontroller will send the required 4 bit signal to the HT12E encoder of RF transmitter circuit. The HT12E will encode the 8 bit address and 4 bit data given to it and then it will transmit the encoded signal serially to the RF module. The RF module will transmit the encoded data and address wirelessly.
 
At the receiver end, the RF receiver module will receive the encoded 4 bit data and 8 bit address. Then, it will transmit the encoded signal serially to the HT12D decoder which will decode the received signal to 8 bit address and 4 bit data. After decoding, the HT12D will compare the received 8 bit address with its local 8 bit address. If the received address and the local address are same, then the received 4 bit data is sent to its output pins else the received data is discarded. The 4 bit output of HT12D is sent to the DC motor driver (L293D) of the robot to drive the robot in the desired direction. Also, the microcontroller will display the direction of movement of the robot in a 16X2 alphanumeric LCD.
 
The control keys for the robot are 2, 8, 4, 6 and 5 to drive the robot in forward, backward, left, right direction and to stop it respectively. Now, press different keys of the 4X3 keypad and drive your robot wirelessly as you want.
 
PROGRAMMING DESCRIPTION:
 
To program ATmega32 microcontroller AVR studio 4 and GCC compiler is used. Guide for using AVR studio 4 see tutorial Working with AVR Studio.
 
Port Pin
 
Define the ports which are connected with the LCD and Keypad. Initialize for the maximum and minimum values for x and y axis at the range where robot to be controlled.
 
Intilization of LCD
 
The main function where operation of the whole project is written, where in this function the pins are declared as input or output pin for the port that are already initialized.
 
Input output ports
 
The while loop inside the main() function is a infinite loop, where the keypad data is read and the conditions are executed to make the robot run.

 

 

Project Source Code

 

Project Source Code

###

//Program to 

#include<avr/io.h>

#include<util/delay.h>
 
#define F_CPU 1000000
 
#define USART_BAUDRATE 9600
#define BAUD_PRESCALE (((F_CPU / (USART_BAUDRATE*16UL))) - 1)
 
#define pad PORTA
#define r1 PA0
#define r2 PA1
#define r3 PA2
#define r4 PA3
 
#define c1 PA4
#define c2 PA5
#define c3 PA6
 
 
// Function prototype to check key pressed from keypad 
void check1(void);
void check2(void);  
void check3(void);
void check4(void);
 
#define LCD_DATA PORTB //LCD data port
 
#define ctrl PORTD
#define en PD2 //enable signal
#define rw PD1 //read/write signal
#define rs PD0 //resister select signal
 
#define CONTROL_OUTPUT PORTC // output port for wireless transmission
 
void LCD_cmd(unsigned char cmd);
void init_LCD(void);
void LCD_write(unsigned char data);
 
void move_forward();
void move_backward();
void turn_left();
void turn_right();
 
unsigned int press;
 
int main()
{
    unsigned char value; 
    DDRC=0x0f; //LCD_DATA port as output port
    DDRB=0xFF; //signal
    DDRA = 0X0F;
    DDRD = 0X07; 
 
    pad = 0xF0;
    init_LCD(); //initialization of LCD
    _delay_ms(50);
    LCD_write_string("EngineersGarage");
    _delay_ms(1000);
    LCD_cmd(0x01);
    LCD_write_string("Keypad Cntrld");
    LCD_cmd(0xC0);
    LCD_write_string("Wireless Robot");
 
    while(1)
    {
PORTA=0xF0; //set all the input to one
value=PINA; //get the PORTD value in variable “value”
if(value!=0xf0) //if any key is pressed value changed
{
    check1();
    check2();
    check3();
    check4();
}
    }
    return 0;
}
 
void check1(void)
{
    pad =0b11111110;
    _delay_us(10);
 
    if(bit_is_clear(PINA,c2))
    {
move_forward();
    }
}
 
 
void check2(void)
{
    pad=0b11111101;
    _delay_us(10);
 
    if(bit_is_clear(PINA,c3))
    {
turn_right();
    }
}
 
void check3(void)
{
    pad=0b11111011;
    _delay_us(10);
 
    if(bit_is_clear(PINA,c2))
    {
move_backward();
    }
}
 
void check4(void)
{
    pad =0b11110111;
    _delay_us(10);
 
    if(bit_is_clear(PINA,c2))
    {
robo_stop();
    }
}
 
 
 
void init_LCD(void)
{
 
    LCD_cmd(0x38); //initializtion of 16X2 LCD in 8bit mode
    _delay_ms(1);
 
    LCD_cmd(0x01); //clear LCD
    _delay_ms(1);
 
    LCD_cmd(0x0E); //cursor ON
    _delay_ms(1);
 
    LCD_cmd(0x80); // ---8 go to first line and --0 is for 0th position
    _delay_ms(1);
    return;
}
 
 
void LCD_cmd(unsigned char cmd)
{
    LCD_DATA=cmd;
    ctrl =(0<<rs)|(0<<rw)|(1<<en); // making RS and RW as LOW and EN as HIGH
    _delay_ms(1);
    ctrl =(0<<rs)|(0<<rw)|(0<<en); // making RS, RW , LOW and EN as LOW
    _delay_ms(50);
    return;
}
 
 
void LCD_write(unsigned char data)
{
    LCD_DATA= data;
    ctrl = (1<<rs)|(0<<rw)|(1<<en); // making RW as LOW and RS, EN as HIGH
    _delay_ms(1);
    ctrl = (1<<rs)|(0<<rw)|(0<<en); // making EN and RW as LOW and RS HIGH
    _delay_ms(50); // give a 10 milli second delay to get thigs executed
    return ;
}
 
void LCD_write_string(unsigned char *str) //take address vaue of the string in pionter *str
{
    int i=0;
    while(str[i]!='') // loop will go on till the NULL charaters is soon in string 
    {
LCD_write(str[i]); // sending data on CD byte by byte
i++;
    }
    return;
}
 
void move_forward()
{
    LCD_cmd(0x01); //clear LCD
    LCD_write_string("   Direction");
    LCD_cmd(0xc0);
    LCD_write_string("Moving Forward");
    CONTROL_OUTPUT = 0x05;
}
 
void move_backward()
{
    LCD_cmd(0x01); //clear LCD
    LCD_write_string("   Direction");
    LCD_cmd(0xc0);
    LCD_write_string("Moving Backward");
    CONTROL_OUTPUT = 0x0A;
}
 
void turn_left()
{
    LCD_cmd(0x01); //clear LCD
    LCD_write_string("   Direction");
    LCD_cmd(0xc0);
    LCD_write_string("Turning Left");
    CONTROL_OUTPUT = 0x08;
}
 
void turn_right()
{
    LCD_cmd(0x01); //clear LCD
    LCD_write_string("   Direction");
    CONTROL_OUTPUT = 0x01;
    LCD_cmd(0xc0);
    LCD_write_string("Turning Right");
}
 
void robo_stop()
{
    LCD_cmd(0x01); //clear LCD
    LCD_write_string("   Direction");
    CONTROL_OUTPUT = 0x00;
    LCD_cmd(0xc0);
    LCD_write_string("     STOP");
}

###

 


Circuit Diagrams

Keypad_Controlled_Wireless_Robot_RX_Circuit_Diagram-Receiver-Side
Keypad_Controlled_Wireless_Robot_TX_Circuit_Diagram-Transmitter-Code


Filed Under: Electronic Projects

 

Next Article

← Previous Article
Next Article →

Questions related to this article?
👉Ask and discuss on EDAboard.com and Electro-Tech-Online.com forums.



Tell Us What You Think!! Cancel reply

You must be logged in to post a comment.

EE TECH TOOLBOX

“ee
Tech Toolbox: 5G Technology
This Tech Toolbox covers the basics of 5G technology plus a story about how engineers designed and built a prototype DSL router mostly from old cellphone parts. Download this first 5G/wired/wireless communications Tech Toolbox to learn more!

EE Learning Center

EE Learning Center
“engineers
EXPAND YOUR KNOWLEDGE AND STAY CONNECTED
Get the latest info on technologies, tools and strategies for EE professionals.

HAVE A QUESTION?

Have a technical question about an article or other engineering questions? Check out our engineering forums EDABoard.com and Electro-Tech-Online.com where you can get those questions asked and answered by your peers!


RSS EDABOARD.com Discussions

  • SMPS feedback circuit
  • How to generate and use large‑signal S‑parameter (LSSP) files for PA harmonic‑balance (HB) simulations?
  • Snooping Around is All
  • ADEM III ECM — No CAN Signal & Power Supply Issue
  • IGBTs without negative gate drive

RSS Electro-Tech-Online.com Discussions

  • More fun with ws2812 this time XC8 and CLC
  • Pic18f25q10 osccon1 settings swordfish basic
  • Pickit 5
  • turbo jet fan - feedback appreciated.
  • I Wanna build a robot

Featured – LoRa/LoRaWan Series

  • What is the LoRaWAN network and how does it work?
  • Understanding LoRa architecture: nodes, gateways, and servers
  • Revolutionizing RF: LoRa applications and advantages
  • How to build a LoRa gateway using Raspberry Pi
  • How LoRa enables long-range communication
  • How communication works between two LoRa end-node devices

Recent Articles

  • How IoT network topologies work
  • The top five AI startups to watch in 2025
  • STMicroelectronics unveils SoC based on secure MCU
  • Nexperia’s 48 V ESD diodes support higher data rates with ultra-low capacitance design
  • Taoglas releases Patriot antenna with 18 integrated elements covering 600 to 6000 MHz

EE ENGINEERING TRAINING DAYS

engineering

Submit a Guest Post

submit a guest post
Engineers Garage
  • Analog IC TIps
  • Connector Tips
  • Battery Power Tips
  • DesignFast
  • EDABoard Forums
  • EE World Online
  • Electro-Tech-Online Forums
  • EV Engineering
  • Microcontroller Tips
  • Power Electronic Tips
  • Sensor Tips
  • Test and Measurement Tips
  • 5G Technology World
  • Subscribe to our newsletter
  • About Us
  • Contact Us
  • Advertise

Copyright © 2025 WTWH Media LLC. All Rights Reserved. The material on this site may not be reproduced, distributed, transmitted, cached or otherwise used, except with the prior written permission of WTWH Media
Privacy Policy

Search Engineers Garage

  • Electronic Projects & Tutorials
    • Electronic Projects
      • Arduino Projects
      • AVR
      • Raspberry pi
      • ESP8266
      • BeagleBone
      • 8051 Microcontroller
      • ARM
      • PIC Microcontroller
      • STM32
    • Tutorials
      • Audio Electronics
      • Battery Management
      • Brainwave
      • Electric Vehicles
      • EMI/EMC/RFI
      • Hardware Filters
      • IoT tutorials
      • Power Tutorials
      • Python
      • Sensors
      • USB
      • VHDL
    • Circuit Design
    • Project Videos
    • Components
  • Articles
    • Tech Articles
    • Insight
    • Invention Stories
    • How to
    • What Is
  • News
    • Electronic Product News
    • Business News
    • Company/Start-up News
    • DIY Reviews
    • Guest Post
  • Forums
    • EDABoard.com
    • Electro-Tech-Online
    • EG Forum Archive
  • DigiKey Store
    • Cables, Wires
    • Connectors, Interconnect
    • Discrete
    • Electromechanical
    • Embedded Computers
    • Enclosures, Hardware, Office
    • Integrated Circuits (ICs)
    • Isolators
    • LED/Optoelectronics
    • Passive
    • Power, Circuit Protection
    • Programmers
    • RF, Wireless
    • Semiconductors
    • Sensors, Transducers
    • Test Products
    • Tools
  • Learn
    • eBooks/Tech Tips
    • Design Guides
    • Learning Center
    • Tech Toolboxes
    • Webinars & Digital Events
  • Resources
    • Digital Issues
    • EE Training Days
    • LEAP Awards
    • Podcasts
    • Webinars / Digital Events
    • White Papers
    • Engineering Diversity & Inclusion
    • DesignFast
  • Guest Post Guidelines
  • Advertise
  • Subscribe