Skip to main content
  1. Resources/
  2. Study Materials/
  3. Electronics & Communication Engineering/
  4. ECE Semester 4/
  5. Microprocessor & Microcontroller (4341101)/

Microprocessor and Microcontroller (4341101) - Summer 2024 Solution

23 mins· ·
Study-Material Solutions Microprocessor 4341101 2024 Summer
Milav Dabgar
Author
Milav Dabgar
Experienced lecturer in the electrical and electronic manufacturing industry. Skilled in Embedded Systems, Image Processing, Data Science, MATLAB, Python, STM32. Strong education professional with a Master’s degree in Communication Systems Engineering from L.D. College of Engineering - Ahmedabad.
Table of Contents

Question 1(a) [3 marks]
#

Describe any one Port Configuration of 8051 Microcontroller.

Answer:

ConfigurationDescription
Port 0Dual-purpose port - 8-bit open drain bidirectional I/O port and multiplexed low address/data bus. External pull-up resistors required for I/O functions.

Diagram:

EP+xu5tlVelr-nuaplsPO8R0T510P(0A.D00--PA0D.77)

Mnemonic: “PORT 0-PLAD” (Port 0 needs Pull-ups, works as Latch/Address/Data)

Question 1(b) [4 marks]
#

Illustrate Microprocessor Architecture.

Answer:

ComponentFunction
ALUPerforms arithmetic and logical operations
RegistersTemporary storage for data and addresses
Control UnitDirects operation of processor and data flow
BusesPathways for data transfer (address, data, control)

Diagram:

ADRAHFDE,,lRGaEIBLgSS,,sASTL,MECSUIR,PDCS,ARDTOPAPCR&OCCEOSNSTORRCIDTCOOneioLNscmnTtoitBRrdnrUOuegoSLcrlEt&SUiNoInT

Mnemonic: “RABC” - “Registers, ALU, Buses, Control”

Question 1(c) [7 marks]
#

Compare Von Neumann & Harvard architecture.

Answer:

FeatureVon Neumann ArchitectureHarvard Architecture
Memory BusesSingle memory bus for instructions and dataSeparate buses for program and data memory
ExecutionSequential executionParallel fetch and execute possible
SpeedSlower due to bus bottleneckFaster due to simultaneous access
Memory AccessSingle memory spaceSeparate memory spaces
ComplexitySimpler designMore complex design
ApplicationsGeneral-purpose computingDSP, microcontrollers, embedded systems
ExamplesMost PCs, 8085, 80868051, PIC, ARM Cortex-M

Diagram:

VonNCePuUmann:Memory|H|arDvaaCtrPadU:Memory|ProgramMemory|

Mnemonic: “Harvard Has Separate Streets” (Harvard Has Separate memory paths)

Question 1(c OR) [7 marks]
#

Define RISC, CISC, Opcode, Operand, Instruction Cycle, Machine Cycle, and T State.

Answer:

TermDefinition
RISCReduced Instruction Set Computer - architecture with simple instructions optimized for speed
CISCComplex Instruction Set Computer - architecture with complex, powerful instructions
OpcodeOperation Code - part of instruction that specifies operation to be performed
OperandData value or address used in operation
Instruction CycleComplete process to fetch, decode and execute an instruction
Machine CycleBasic operation like memory read/write (subset of instruction cycle)
T-StateTime state - smallest unit of time in processor operation (clock period)

Diagram:

ITn-sSTtFt1rEauTtcCeMtHsaiTcow2hniitnCheyicnTCl3yeMc:alcehiTDn4EeCOCDyEcle:EXECUTE

Mnemonic: “RICO ITEM” (RISC, CISC, Opcode, Instruction cycle, T-state, Execute, Machine cycle)

Question 2(a) [3 marks]
#

Define Data bus, Address bus and Control bus.

Answer:

Bus TypeDefinition
Data BusBidirectional pathway that transfers actual data between microprocessor and peripheral devices
Address BusUnidirectional pathway that carries memory/IO device locations to be accessed
Control BusGroup of signal lines that coordinate and synchronize all system operations

Diagram:

CPUA(D(C(dMaIoRdetnnDrmaft,eoorWsrBroRsyuml,/saIBItBOuOiu/sosMln.o).c.))

Mnemonic: “ADC” - “Address finds location, Data carries information, Control coordinates operations”

Question 2(b) [4 marks]
#

Compare Microprocessor and Microcontroller.

Answer:

FeatureMicroprocessorMicrocontroller
DefinitionCPU on a single chipComplete computer system on a chip
MemoryExternal RAM/ROM neededBuilt-in RAM/ROM
I/O PortsLimited or none on-chipMultiple I/O ports on-chip
PeripheralsExternal peripherals neededBuilt-in peripherals (timers, ADC, etc.)
ApplicationsGeneral computing, PCsEmbedded systems, IoT devices
CostHigher for complete systemLower (all-in-one solution)
Power ConsumptionHigherLower

Mnemonic: “MEMI-CAP” (Memory external/internal, Cost, Applications, Peripherals)

Question 2(c) [7 marks]
#

Sketch and explain 8085 block diagram.

Answer:

Diagram:

ADARAABSWDDER,,P,IDRDBGRFC,ZNAERUIAl,(TTSESSYaDPTAEASSTg,CeLR,SEsEmUNBR,pAUDH)LSA,TLA8DB0&AU8TS5CAOCNPTUROLCTCIDICBOIOnenoUNBMNsctnSTUITtoetRSNRrdrrIOGOueroNLLcrulT&tpEitRoFnACE

Main Components:

  • Register Array: A (Accumulator), Flags, B-L, SP, PC, temp registers
  • ALU: Performs arithmetic and logical operations
  • Timing & Control: Generates control signals, handles interrupts
  • Bus Interface: Connects CPU to external devices
  • Internal Data Bus: Links internal components

Mnemonic: “RATBI” - “Registers, ALU, Timing, Buses, Interface”

Question 2(a OR) [3 marks]
#

Explain Accumulator, Program Counter and Stack Pointer.

Answer:

RegisterFunction
Accumulator (A)8-bit register that stores results of arithmetic and logical operations
Program Counter (PC)16-bit register that holds address of next instruction to be executed
Stack Pointer (SP)16-bit register that points to current top of stack in memory

Diagram:

ADcactuamAuolpaetroart:ionsPPironoisgntrtrasumcPttCCoioounnnetxetr:SPstotaiacncktksPtoStoiPopnter:SMteamcokry

Mnemonic: “APS” - “Accumulator Processes, PC Predicts, SP Stacks”

Question 2(b OR) [4 marks]
#

Sketch and explain Demultiplexing of Address bus and data bus.

Answer:

Diagram:

AA1D57--AA8D08A0L8E5CPUA17L54a-LtASc83h7(3HigherAAd7d-rAe0ss()LowerAddress)

Process:

  1. Multiplexing: AD0-AD7 pins share address and data signals to reduce pin count
  2. Demultiplexing Steps:
    • CPU places address on AD0-AD7 pins
    • ALE (Address Latch Enable) signal goes HIGH
    • External latch (74LS373) captures lower address bits
    • ALE goes LOW, latching the address
    • AD0-AD7 pins now carry data

Mnemonic: “ALAD” - “ALE Active, Latch Address, After Data”

Question 2(c OR) [7 marks]
#

List any seven features of 8085.

Answer:

FeatureDescription
8-bit Data BusTransfers 8 bits of data in parallel
16-bit Address BusCan address up to 64KB of memory (2^16)
Hardware Interrupts5 hardware interrupts (TRAP, RST 7.5, 6.5, 5.5, INTR)
Serial I/OSID and SOD pins for serial communication
Clock GenerationOn-chip clock generator with crystal
Instruction Set74 operation codes generating 246 instructions
Register SetSix 8-bit registers (B,C,D,E,H,L), accumulator, flags, SP, PC

Diagram:

1AS8DB6dBeI-au-dur/btsbrsiOiaieattsls8085Featur5IL7OOCeni4pnlsHtnc-oWeeoccrsdhkreiusppt

Mnemonic: “CHAIRS” - “Clock, Hardware interrupts, Address bus, Instruction set, Registers, Serial I/O”

Question 3(a) [3 marks]
#

Illustrate any one Timer Mode of 8051.

Answer:

Mode 1: 16-bit Timer/Counter

FeatureDescription
Timer Structure16-bit timer using THx and TLx registers
OperationCounts from 0000H to FFFFH, then sets TF flag
Counter SizeFull 16-bit counter (2^16 = 65,536 counts)
RegistersTHx (high byte) and TLx (low byte)

Diagram:

ClCBooicntktsrSoolurceGC(aoT1tnH6etx-r:boTilLtxTcFCoou(unTntiODtemveereetr)rrefcFltloawgT)Fx

Mnemonic: “MOGC” - “Mode 1 uses Overflow detection, Gate control, Complete 16-bits”

Question 3(b) [4 marks]
#

State function of ALE, PSEN, RESET and TXD pin for 8051.

Answer:

PinFunction
ALEAddress Latch Enable - Provides control signal to latch low byte of address from port 0
PSENProgram Store Enable - Read strobe for external program memory access
RESETReset input - Forces CPU to initial state when held HIGH for 2 machine cycles
TXDTransmit Data - Serial port output pin for serial data transmission

Diagram:

RAPE8LSS0EEE5NT1--Pi8n05F1unctiToXnDs

Mnemonic: “APTR” - “Address latch, Program store, Total reset, tRansmit data”

Question 3(c) [7 marks]
#

Explain functions of each block of 8051 Microcontroller.

Answer:

BlockFunction
CPU8-bit processor that fetches and executes instructions
Memory4KB internal ROM and 128 bytes of internal RAM
I/O PortsFour 8-bit bidirectional I/O ports (P0-P3)
Timers/CountersTwo 16-bit timers/counters for timing and counting
Serial PortFull-duplex UART for serial communication
InterruptsFive interrupt sources with two priority levels
Clock CircuitProvides timing for all operations

Diagram:

MReACmMPo/UrRyOMCl8o0Cc5ToSk1iuePmnroCAetiriRreatrCsrlcH/suIiTtECTUREPI0I/,nOPt1eP,roPrr2ut,psPt3s

Mnemonic: “CRIMSON” - “CPU, RAM/ROM, I/O, Memory, Serial port, Oscillator, iNterrupts”

Question 3(a OR) [3 marks]
#

Illustrate any one Serial Communication Mode of 8051.

Answer:

Mode 1: 8-bit UART

FeatureDescription
Format10 bits (start bit, 8 data bits, stop bit)
Baud RateVariable, determined by Timer 1
Data DirectionFull-duplex (simultaneous transmit and receive)
Pins UsedTXD (P3.1) for transmit, RXD (P3.0) for receive

Diagram:

Timer1BGRSaeehunciSdeefSBritBURavUFateRFtoeergSPTSe3Prhr.3aii0.nfa1stl(mR(iRIXTtenDXg)D)SerialOut

Mnemonic: “FADS” - “Format 10-bit, Auto baud from Timer 1, Duplex mode, Standard UART”

Question 3(b OR) [4 marks]
#

State function of RXD, INT0, T0 and PROG pin for 8051.

Answer:

PinFunction
RXD (P3.0)Receive Data - Serial port input pin for serial data reception
INT0 (P3.2)External Interrupt 0 - Input that can trigger external interrupt
T0 (P3.4)Timer 0 - External count input for Timer/Counter 0
PROG (EA)Program Enable - When LOW, forces CPU to fetch code from external memory

Diagram:

RIT8XN00DT501-Pi8n05F1unctiPoRnOsG

Mnemonic: “RIPE” - “Receive data, Interrupt trigger, Pulse counting, External memory”

Question 3(c OR) [7 marks]
#

Describe ALU, PC, DPTR, RS0, RS1, Internal RAM and Internal ROM of 8051.

Answer:

ComponentDescription
ALUArithmetic Logic Unit - Performs math and logical operations
PCProgram Counter - 16-bit register that points to next instruction
DPTRData Pointer - 16-bit register (DPH+DPL) for external memory addressing
RS0, RS1Register Bank Select bits in PSW - Select one of four register banks
Internal RAM128 bytes on-chip RAM (00H-7FH) for variables and stack
Internal ROM4KB on-chip ROM (0000H-0FFFH) for program storage

Diagram:

8I0n5t1I(eSBR(n4rcieRMtKnrtgSeeBaa-i0mr)ltas,oncdtRraRhdeSylArr1MPeOR:asBsrOdsaegManlabkenlscietz)atio007320nF0F000:F0HHHHF0HH

Mnemonic: “APRID” - “ALU Processes, PC Remembers, Register bank select, Internal memory, DPTR points”

Question 4(a) [3 marks]
#

Develop an Assembly language program to divide 08H by 02H.

Answer:

      MOV A, #08H    ; Load dividend 08H into accumulator
      MOV B, #02H    ; Load divisor 02H into B register
      DIV AB         ; Divide A by B (A=quotient, B=remainder)
      MOV R0, A      ; Store quotient in R0 (04H)
      MOV R1, B      ; Store remainder in R1 (00H)

Diagram:

BefABo::re0082DHHIVAB:AftABe::r00D40IHHVAB((:QRueomtaiienndte)r)

Mnemonic: “LDDS” - “Load dividend, Divisor in B, Divide, Store results”

Question 4(b) [4 marks]
#

Develop an Assembly language program to add 76H and 32H.

Answer:

      MOV A, #76H    ; Load first number 76H into accumulator
      MOV R0, #32H   ; Load second number 32H into R0
      ADD A, R0      ; Add R0 to A (76H + 32H = A8H)
      MOV R1, A      ; Store result in R1 (A8H)
      JNC DONE       ; Jump if no carry
      MOV R2, #01H   ; If carry occurred, store 1 in R2
DONE: NOP            ; End program

Diagram:

Ca+7l6c73AHu628lHHHat===i+o001n100?:11111000131002110H000=?A8H+CarryFlag

Mnemonic: “LASER” - “Load A, Store second number, Execute addition, Result stored”

Question 4(c) [7 marks]
#

What is Addressing mode? Classify it for 8051.

Answer:

Addressing Mode: Method to specify the location of operand/data for an instruction.

Addressing ModeDescriptionExample
RegisterOperand in registerMOV A, R0 (Move R0 to A)
DirectOperand at specific memory locationMOV A, 30H (Move data from 30H to A)
Register IndirectRegister contains address of operandMOV A, @R0 (Move data from address in R0 to A)
ImmediateOperand is part of instructionMOV A, #55H (Load A with 55H)
IndexedBase address + offsetMOVC A, @A+DPTR (Get code byte at A+DPTR)
BitIndividual bit addressableSETB P1.0 (Set bit 0 of Port 1)
Implied/InherentOperand implied by instructionRRC A (Rotate A right with carry)

Diagram:

RMeOgVAisAt,erR5R5DMiOrVAecAt,40H40HIMnOdVAirAe,ct@R1RX1=X

Mnemonic: “RIDDIB” - “Register, Immediate, Direct, Data indirect, Indexed, Bit”

Question 4(a OR) [3 marks]
#

Develop an Assembly language program to multiply 08H and 02H.

Answer:

      MOV A, #08H    ; Load first number 08H into accumulator
      MOV B, #02H    ; Load second number 02H into B register
      MUL AB         ; Multiply A and B (B:A = result)
      MOV R0, A      ; Store low-byte result in R0 (10H)
      MOV R1, B      ; Store high-byte result in R1 (00H)

Diagram:

BefABo::re0082MHHULAB:AftABe::r10M00UHHLAB((:0H8iHgh×b0y2tHe==1000HH))

Mnemonic: “LMSR” - “Load numbers, Multiply, Store Result”

Question 4(b) [4 marks]
#

Develop an Assembly language program to subtract 76H from 32H.

Answer:

      MOV A, #32H    ; Load 32H into accumulator
      MOV R0, #76H   ; Load 76H into R0
      CLR C          ; Clear carry flag (borrow flag)
      SUBB A, R0     ; Subtract R0 from A with borrow (32H - 76H = BCH)
      MOV R1, A      ; Store result in R1 (BCH, which represents -44H)

Diagram:

Ca-3l2c37BHu26ClHHHat===i-o001n010?:11111100170116110H000(tw=o'?scoBmCpHlement(orfep4r4eHs)ents-44H)

Mnemonic: “LESS” - “Load first number, Enable borrow (CLR C), Subtract, Store”

Question 4(c) [7 marks]
#

List types of instruction set. Explain any three with one example.

Answer:

Instruction GroupDescriptionExample
ArithmeticMathematical operationsADD A, R0 (Add R0 to A)
LogicalLogical operationsANL A, #0FH (AND A with 0FH)
Data TransferMove data between locationsMOV A, R7 (Move R7 to A)
BranchChange program flowJNZ LOOP (Jump if A not zero)
Bit ManipulationOperate on individual bitsSETB P1.0 (Set bit 0 of Port 1)
Machine ControlControl processor operationNOP (No operation)

Explained Instructions:

  1. Data Transfer Instructions:

    • Move data between registers, memory, or I/O ports
    • Example: MOV A, 30H - Moves data from memory location 30H to accumulator
    • Operation: A ← [30H]
  2. Arithmetic Instructions:

    • Perform mathematical operations like addition, subtraction, etc.
    • Example: ADD A, R0 - Adds content of R0 to accumulator
    • Operation: A ← A + R0
  3. Logical Instructions:

    • Perform logical operations like AND, OR, XOR, NOT
    • Example: ANL A, #0FH - Masks upper nibble (keeps only lower nibble)
    • Operation: A ← A AND 0FH

Diagram:

DTAILIarrnontaisgsanttitshrcrfmuaueeclcrtttiii8coo0nn5ss1InstrucBIBMMCtrniaaoiastncnontihtncrpirhuunoTclelytapiteoisnosn

Mnemonic: “BALDM” - “Branch, Arithmetic, Logical, Data transfer, Machine control”

Question 5(a) [3 marks]
#

Sketch interfacing of four LEDs with 8051 Microcontroller.

Answer:

Diagram:

RL1ED1P1.0RLP+2E15D.V218051RLP3E1D.32RLP4E1D.43(220Ωresistors)

Components:

  • 8051 microcontroller
  • Four LEDs
  • Four current limiting resistors (220Ω)
  • Power supply

Mnemonic: “PALS” - “Port pins, Active-low control, LEDs, Simple circuit”

Question 5(b) [4 marks]
#

Sketch interfacing of 7 segment LED with 8051 Microcontroller.

Answer:

Diagram:

PPPPPPP1111111.......01234568abcdefg05sd1eiG+7gsN5mpDVelnaty

Components:

  • 8051 microcontroller
  • 7-segment LED display (common cathode)
  • Seven current limiting resistors (not shown)
  • Power supply

Code Example:

; Define segment patterns for digits 0-9
DIGITS: DB 3FH, 06H, 5BH, 4FH, 66H, 6DH, 7DH, 07H, 7FH, 6FH
  
; Display digit 5
MOV A, #6DH      ; Segment pattern for 5
MOV P1, A        ; Send to port P1

Mnemonic: “SPACE-7” - “Seven Pins, Active segments, Common ground, Easy display”

Question 5(c) [7 marks]
#

Explain interfacing of DAC with 8051 Microcontroller and write necessary program.

Answer:

Diagram:

8051--PP13..00--P-1-.-7------->>DC0DS-+G-A55NDCVVD70808-Output-->FilterAOnuatlpougt

Components:

  • 8051 microcontroller
  • DAC0808 (8-bit digital-to-analog converter)
  • Operational amplifier for output buffering
  • RC filter for smoothing
  • Power supply

Connections:

  • P1.0-P1.7 → D0-D7 (8-bit digital input)
  • P3.0 → CS (Chip Select)

Program for generating a sawtooth wave:

START:  MOV R0, #00H     ; Initialize R0 to 0
LOOP:   MOV P1, R0       ; Output value to DAC
        CALL DELAY       ; Wait for some time
        INC R0           ; Increment value
        SJMP LOOP        ; Repeat to create sawtooth wave

DELAY:  MOV R7, #50      ; Load delay counter
DELAY1: MOV R6, #255     ; Inner loop counter
DELAY2: DJNZ R6, DELAY2  ; Decrement R6 until zero
        DJNZ R7, DELAY1  ; Decrement R7 until zero
        RET              ; Return from subroutine

Working Principle:

  1. Digital value is output on Port 1
  2. DAC converts 8-bit digital value to proportional analog voltage
  3. Filter smooths the output signal
  4. Program creates a sawtooth wave by incrementing output value

Mnemonic: “DICAF” - “Digital input, Increment, Convert to analog, Amplify, Filter”

Question 5(a OR) [3 marks]
#

Sketch interfacing of four Switches with 8051 Microcontroller.

Answer:

Diagram:

+5VP1R10e.Ks0ΩisPtuoPlr18ls.0-15u1pS1P1.2P1S.23S3S4

Components:

  • 8051 microcontroller
  • Four push buttons (normally open)
  • Pull-up resistors (10KΩ)
  • Power supply

Working Principle:

  • Switches connect to ground when pressed
  • Port pins read HIGH (1) when switch open
  • Port pins read LOW (0) when switch pressed

Mnemonic: “PIPS” - “Pull-ups, Input pins, Press for zero, Switches”

Question 5(b) [4 marks]
#

Sketch interfacing of Stepper motor with 8051 Microcontroller.

Answer:

Diagram:

8051----PPPP1111....0123-------->>>>UDLr+Ni12v20eV0r3----OOOOuuuutttt1234--------ABCDStMeoptpoerr

Components:

  • 8051 microcontroller
  • ULN2003 driver IC
  • Stepper motor (4-phase)
  • Power supply

Excitation Sequence:

StepP1.3 (D)P1.2 (C)P1.1 (B)P1.0 (A)Hex Value
1000101H
2001002H
3010004H
4100008H

Mnemonic: “CUPS” - “Controller outputs sequence, ULN2003 amplifies, Phases energized, Stepping motion”

Question 5(c) [7 marks]
#

Explain interfacing of ADC with 8051 Microcontroller and write necessary program.

Answer:

Diagram:

AIV+G+nnR5N5apEVDVluF---ot/---g-2------------------>>>>>+VGI5AcNNVDcDTCR0804-D0-D7-----CRW-SDR---------------->---P1PPP.33308...-0012P511.7

Components:

  • 8051 microcontroller
  • ADC0804 (8-bit analog-to-digital converter)
  • Reference voltage source
  • Input conditioning circuit (not shown)

Connections:

  • P1.0-P1.7 ← D0-D7 (8-bit digital output from ADC)
  • P3.0 → CS (Chip Select)
  • P3.1 → RD (Read)
  • P3.2 → WR (Write)

Program for reading analog input:

START:  MOV P1, #0FFH    ; Configure P1 as input port
        
READ:   CLR P3.0         ; Enable ADC (CS = 0)
        CLR P3.2         ; Start conversion (WR = 0)
        NOP              ; Small delay
        NOP
        SETB P3.2        ; WR = 1
        
WAIT:   JB P3.3, WAIT    ; Wait for conversion (INTR = 0)
        
        CLR P3.1         ; RD = 0 to read data
        MOV A, P1        ; Read converted value
        SETB P3.1        ; RD = 1
        SETB P3.0        ; Disable ADC (CS = 1)
        
PROCESS:                 ; Process the data as needed
        ; Example: Store in R0
        MOV R0, A
        
        SJMP READ        ; Repeat for continuous conversion

Working Principle:

  1. Controller sends start conversion signal
  2. ADC converts analog input to 8-bit digital value
  3. Controller reads digital value after conversion complete
  4. Program processes the digital value as required

Mnemonic: “CARSW” - “Convert Analog, Read Digital, Start conversion, Wait for completion”

Related

Microprocessor and Microcontroller (4341101) - Winter 2024 Solution
23 mins
Study-Material Solutions Microprocessor 4341101 2024 Winter
Microprocessor and Microcontroller (4341101) - Summer 2023 Solution
23 mins
Study-Material Solutions Microprocessor 4341101 2023 Summer
Fundamentals of Electrical Engineering (4311101) - Summer 2024 Solution
18 mins
Study-Material Solutions Electrical-Engineering 4311101 2024 Summer
Java Programming (4343203) - Summer 2024 Solution
17 mins
Study-Material Solutions Java-Programming 4343203 2024 Summer
Linear Integrated Circuit (4341105) - Summer 2024 Solution
20 mins
Study-Material Solutions Linear-Integrated-Circuit 4341105 2024 Summer
Database Management System (1333204) - Summer 2024 Solution
20 mins
Study-Material Solutions Database 1333204 2024 Summer