Arduino Microcontroller Development
Arduino is an open-source ecosystem including:
- Hardware schematics, and PCB layouts for the Arduino micro-controller boards.
- A bootloader for the Arduino platform, and a Software Development Kit (SDK).
- A cross-platform Integrated Development Environment (IDE) (written in Java).
Arduino is build with an AVR Atmel micro-controller, the required power supply, a clock crystal, and female input/output pins to interface with peripherals.
Arduino exist in many flavors: Uno, Leonardo, Mega, Nano, Mini, etc.
I.e. the Arduino UNO R3 hosts an ATmega328 micro-controller:
- Low-power CMOS 8bit micro-controller (AVR enhanced RISC architecture)
- Available as through-hole DIP, and as surface mounted device (SMD)
- Runs with 16Mhz clock speed at 5V
- 32kB Flash non-volatile memory (to store programs persistently)
- 2kB SRAM random access memory used to store program run-time data
- 1kB EEPROM non-volatile memory for system configuration
The host Computer is the workstation of the programmer:
- Used to implement software for the micro-controller on the Arduino board
- Used to translate (compile) this software into the micro-controller binary machine-code
- Used to transfer the binary code onto the flash memory on the Arduino board
The target computer is the Arduino itself connected via USB.
Typical development cycle in steps:
- Write code for the Arduino micro-controller, a program.
- Compile this program into (binary) machine-code understood by the micro-controller
- Transfer the machine-code to the Arduino device micro-controller
- Execute the program on the micro-controller for testing & debugging
- Repeat
Install
Arduino IDE 2.x from FlatHub…
# ...add FlatHub to the repository list
flatpak remote-add --if-not-exists \
flathub https://flathub.org/repo/flathub.flatpakrepo
# ...install the IDE
flatpak install cc.arduino.IDE2
# run with permissions to access the network and USB devices...
flatpak run --share=network --device=all cc.arduino.IDE2 &
# check permissions with
flatpak info -M cc.arduino.IDE2Download the latest version from the Arduino project…
mkdir -p ~/arduino && cd ~/arduino
# extract the downloaded archive & rename the directory
version=1.8.11
tar -xvf ~/Downloads/arduino-$version-linux64.tar.xz && mv arduino-$version $version
# run the installer
sudo ~/arduino/$version/install.sh
# add ARDUINO_HOME to your shell environment, e.g.:
test -d ~/.zshrc.d && \
echo "export ARDUINO_HOME=~/arduino/$version\nexport PATH=\$ARDUINO_HOME:\$PATH" \
> ~/.zshrc.d/arduinoConnect an Arduino the computers USB port!
Find the device used for the communication over USB and the user group allowed to access it
# show serial USB devices
find /dev -name 'ttyACM*' -o -name 'ttyUSB*' | xargs stat --printf "%n %G\n"Add your user account permanently to the required group (e.g. dialout) to use serial ports:
# Debian & Fedora
sudo gpasswd -a $USER dialout ; newgrp dialout
# arch
sudo gpasswd -a $USER uucp ; newgrp uucpRe-login to make the change active!
Tools
The Arduino integrated development environment (IDE) includes a code editor, and provides simple one-click mechanisms to compile and upload programs to an Arduino board.
- Start the Arduino IDE, and connect the Arduino board to USB.
- Select the right Arduino board in the Tools ➝ Board menu, e.g. “Arduino/Genuino Uno”
- Select the connection port in the Tools ➝ Port menu, e.g.
/dev/ttyACM0. - Select the Blink program in the File ➝ Examples ➝ 01.Basics menu.
- Press the Upload button (arrow right) beneath the menu, or press Ctrl-u.
Configure the Sketchbook location in the File ➝ Preferences menu to the source directory src/.
- Arduino program files (extension
.ino) require an enclosing sketch folder. - The main-program file needs to be called like the sketch folder.
- Load sketches from File ➝ Sketchbook
Serial Monitor
A serial monitor displays the data transmitted via serial communication
- The Arduino IDE has a build in monitor (start with CTRL-SHIFT-m)
- The Arduino Makefile support the command
make monitor
# use GNU Screen for serial communication
screen /dev/ttyACM0 9600
# or minicom
minicom -D /dev/ttyACM0 -b 9600 Makefile
Install the latest Arduino-Makefile from GitHub:
# path to the installation
ARDMK_DIR=~/projects/arduino-makefile
# clone the Git repository
git clone https://github.com/sudar/Arduino-Makefile.git $ARDMK_DIR
# add ARDMK_DIR to your shell environment, e.g.:
echo "export ARDMK_DIR=$ARDMK_DIR\nexport PATH=\$ARDMK_DIR/bin:\$PATH" > ~/.zshrc.d/21_ardmkFollowing an example Makefile using ARDUINO_HOME as path to the Arduino software:
>>> grep -e ARD -e AVR $AVR_HOME/src/io/gpio/blink/Makefile
ARDUINO_DIR = $(ARDUINO_HOME)
AVR_TOOLS_DIR = $(ARDUINO_HOME)/hardware/tools/avr/
AVRDUDE = $(AVR_TOOLS_DIR)/bin/avrdude
AVRDUDE_CONF = $(AVR_TOOLS_DIR)/etc/avrdude.confUse the make command to compile the source code, and make upload to flash the binary to the Arduino:
>>> cd $AVR_HOME/src/io/gpio/blink
# build
>>> make && ls build-uno/*.hex
build-uno/led_blink.hex
# upload to the MCU
>>> make upload
# remove build artifacts
>>> make cleanAdjust the BOARD_TAG and MONITOR_PORT according to the Arduino used. For example to compile and upload to and Arduino Nano:
## Configure the Makefile for the Arduino Nano
>>> grep -e ^BOARD -e PORT Makefile
BOARD_TAG = nano328
MONITOR_PORT = /dev/ttyUSB0Arduino CLI
Arduino CLI …download from the releases page…
cd /tmp
wget https://github.com/arduino/arduino-cli/releases/download/0.7.2/arduino-cli_0.7.2_Linux_64bit.tar.gz
tar -xvf arduino-cli_0.7.2_Linux_64bit.tar.gz
sudo mv arduino-cli /usr/local/binUpdate the local cache of available platforms and libraries:
arduino-cli core update-indexCores
Connect a board via an USB cable:
# list connected boards
>>> arduino-cli board list
Port Type Board Name FQBN Core
/dev/ttyACM0 Serial Port (USB) Arduino Uno arduino:avr:uno arduino:avr
/dev/ttyAMA0 Serial Port Unknown
/dev/ttyUSB0 Serial Port (USB) UnknownUnknown boards should work as long you identify the platform core and use the correct FQBN string
Install the corresponding core to support the board
>>> arduino-cli core install arduino:avr
>>> arduino-cli core list
ID Installed Latest Name
arduino:avr 1.8.2 1.8.2 Arduino AVR Boards
# search for a supported board
>>> arduino-cli board listall nano
Board Name FQBN
Arduino Nano arduino:avr:nanoSketch
Create a new Sketch
arduino-cli sketch new blink
# creates a new sub-directory blink/
cat > blink/blink.ino <<EOF
void setup() {
pinMode(LED_BUILTIN, OUTPUT);
}
void loop() {
digitalWrite(LED_BUILTIN, HIGH);
delay(1000);
digitalWrite(LED_BUILTIN, LOW);
delay(1000);
}
EOFfqbn=arduino:avr:uno
port=/dev/ttyACM0
# build and flash for an Arduino Uno
arduino-cli compile --fqbn arduino:avr:uno blink
arduino-cli upload -p /dev/ttyACM0 -b arduino:avr:uno blink
# build and flash for an Arduino Nano
arduino-cli compile -b arduino:avr:nano blinkAVR Compiler
List of files in this example:
| File | Format | Description |
|---|---|---|
blink.c |
ASCII | C program source code (higher programming language) |
blink.eln |
ELF | Relocatable binary-object file (output from the assembler, input to the linker) |
blink.elf |
ELF | Executable binary-object file (output from the linker) |
blink.hex |
ASCII | Hexadecimal encoded binary machine code loaded to the MCU ROM |
blink.lst |
ASCII | List-file with assembler source and interspaces C source code |
blink.map |
ASCII | Map-file showing symbol reference to modules(/libraries) |
Compile
The avr-gcc program compiles C-code for Atmel AVR micro-controllers (MCUs):
-mmucspecifies the MCU type (cf. Machine-specific options for the AVR)-g- Embed debug info later disassembling (inflates the code!)-c- Disable linking, will be down in an additional step
avr-gcc -mmcu=atmega328p -g -c -o /tmp/blink.eln $AVR_HOME/src/blink.c # compile
avr-gcc -mmcu=atmega328p -g -o /tmp/blink.elf /tmp/blink.eln # linkThe avr-objdump program manipulats object files:
-S- Disassembles the binary file and intersperses the source code.- The result list-file allows to better understand the translation between assembler and C-code
avr-objdump -h -S /tmp/blink.elf > /tmp/blink.lst # disassembleGenerate a map-file during linking which shows where modules are loaded and which modules were loaded from libraries.
avr-gcc -mmcu=atmega328p -g -Wl,-Map,/tmp/blink.map -o /tmp/blink.elf /tmp/blink.eln # re-linkUpload
The binary format ELF (Executable and Linking Format) is not compatible with flash program.
Extract the required segments from the object-file and encode into hex:
avr-objcopy -j .text -j .data -O ihex /tmp/blink.elf /tmp/blink.hexWrite the hex-encoded program to the Arduino Uno ROM (memory) and reset the MCU:
avrdude -p atmega328p -c arduino -P /dev/ttyACM0 -U flash:w:/tmp/blink.hex:iOptions to avrdude depend on the Arduino used. The following configuration is used to an Arduino Nano:
avrdude -p atmega328p -c arduino -P /dev/ttyUSB0 -b 57600 -U flash:w:/tmp/blink.hex:iScript
A simple shell-script to compile and flash a single file program to an Arduino:
# defaults fot the Arduino Uno
export AVR_DEVICE=/dev/ttyACM0
export AVR_MCU=atmega328p
export AVR_BAUDRATE=115200
function avr-upload() {
local source=$1
local name=${source%%.*}
local object=/tmp/$name.elf
local hex=/tmp/$name.hex
avr-gcc -mmcu=$AVR_MCU -o $object $source && \
avr-objcopy -O ihex $object $hex && \
avrdude -q -p $AVR_MCU -c arduino -P $AVR_DEVICE -b $AVR_BAUDRATE -U flash:w:$hex:i
}Serial Communication
The Arduino uses UART to:
- Upload a program from the computer to the Arduino
- Connects with a serial monitor to send and receive data from an Arduino during program execution
Arduino has at least one serial port connected to the micro-controller:
- Data transmission on the serial port is indicator by the TX/RX LEDs on the board
- TX means transmit and RX means receive
- Also connected to pins 0 (RX) and 1 (TX)
- Dedicated chip to convert the hardware serial port (TTL) to USB (Universal Serial Bus)
AVR USART features:
- Full duplex operation, RX (receive) & TX (transmit) at the same time
- Synchronous or asynchronous
- High resolution baud rate generator (minimum error)
- 5 to 9 data bits, 1 or 2 stop bits, odd/even parity generator
- Double speed asynchronous communication mode
- 3 interrupt sources (TX complete, RX complete, TX data register empty)
- Supports SPI mode
Baud Rate
12-bit register contains the USART baud rate
| Register | USART Baud Rate |
|---|---|
| UBRR0H[3:0] | Baud Rate 0 Register High |
| UBRR0L[7:0] | Baud Rate 0 Register Low |
Status register:
| Bit | UCSR0A | Control and Status Register 0 A |
|---|---|---|
| 1 | U2X0 | Double Transmission Speed |
- Writing
UBRR0Lwill trigger an immediate update of the baud rate pre-scaler - Ongoing transmissions corrupted if the baud rate is changed
- External clock pin XCK (PD4)
- U2X0 enables double transmission speed in asynchronous operation
- Logic zero in synchronous operation
- Logic one will reduce the divisor of the baud rate divider from 16 to 8 effectively doubling the transfer
UCSR0A |= (0<<U2X0) // single transmission speed
UCSR0A |= (1<<U2X0) // double transmission speedUCSR0A |= (0<<U2X0)
UBRR0L = 103 // 9600bps@16MHz
UBRR0L = 25 // 115.2kbps@16MHz
UBRR0L = 0 // 1Mbps@16MHz
UCSR0A |= (1<<U2X0)
UBRR0L = 1 // 1Mbps@16MHz
UBRR0L = 0 // 2Mbps@16MHz
Configuration
| Bit | UCSR0A | Control and Status Register 0 A |
|---|---|---|
| 0 | MPCM0 | Multi-processor Communication Mode |
| Bit | UCSR0B | Control and Status Register 0 B |
|---|---|---|
| 4 | RXEN0 | Receiver Enable |
| 3 | TXEN0 | Transmitter Enable |
| 2 | UCSZ02 | Character Size (combined with UCSR0C.UCSZ0[1:0]) |
UCSR0B |= (1<<RXEN0) | (1<<TXEN0); // enables the USART transmitter/receiver| Bit | UCSR0C | Control and Status Register 0 C |
|---|---|---|
| 7:6 | UMSEL0[1:0] | Mode Select |
| 5:4 | UPM0[1:0] | Parity Mode |
| 3 | USBS0 | Stop Bit Select |
| 2:1 | UCSZ0[1:0] | Character Size (combined with UCSR0B.UCSZ02) |
| 0 | UCPOL0 | Clock Polarity XCK0 (logic zero falling, logic one rising) |
Select from these configurations:
// USART Mode Select
UCSR0C |= (0<<UMSEL01) | (0<<UMSEL00); // asynchronous (default)
UCSR0C |= (0<<UMSEL01) | (1<<UMSEL00); // synchronous
UCSR0C |= (1<<UMSEL01) | (1<<UMSEL00); // master SPI
// USART Parity Mode
UCSR0C |= (0<<UPM01) | (0<<UPM00); // disbaled (default)
UCSR0C |= (1<<UPM01) | (0<<UPM00); // enable, even parity
UCSR0C |= (1<<UPM01) | (1<<UPM00); // enable, odd parity
// USART Stop Bit Select
UCSR0C |= (0<<USBS0); // 1-bit (default)
UCSR0C |= (1<<USBS0); // 2-bit
// USART Character Size / Data Order
UCSR0C |= (0<<UCSZ02) | (0<<UCSZ01) | (0<<UCSZ00); // 5-bit (default)
UCSR0C |= (0<<UCSZ02) | (0<<UCSZ01) | (1<<UCSZ00); // 6-bit
UCSR0C |= (0<<UCSZ02) | (1<<UCSZ01) | (0<<UCSZ00); // 7-bit
UCSR0C |= (0<<UCSZ02) | (1<<UCSZ01) | (1<<UCSZ00); // 8-bit
UCSR0C |= (1<<UCSZ02) | (1<<UCSZ01) | (1<<UCSZ00); // 9-bitTransmit/Receive
Data registers (receive pin RxD (PD0), transmit pin TxD (PD1)):
| UDR0 | I/O Data Register |
|---|---|
| TXB[7:0] | TX Transmit buffer |
| RXB[7:0] | RX Receive buffer |
| Bit | UCSR0B[1:0] | Control and Status Register 0 B |
|---|---|---|
| 1 | RXB80 | Receive Data Bit 8 |
| 0 | TXB80 | Transmit Data Bit 8 |
Status registers:
| Bit | UCSR0A | Control and Status Register 0 A |
|---|---|---|
| 7 | RXC0 | Receive Complete |
| 6 | TXC0 | Transmit Complete |
| 5 | UDRE0 | Data Register |
| 4 | FE0 | Frame Error |
| 3 | DOR0 | Data OverRun |
| 2 | UPE0 | Parity Error |
- TX and RX share the same I/O address referred UDR0
- UDR0 holds data for 5 to 8-bit communication
- Data bit 9 in combination with
UCSR0B.RXB80orUCSR0B.TXB80
- UDRE0 indicates whether the transmit buffer is ready to receive new data
- Set when the transmit buffer is empty
- Cleared when the transmit buffer contains data to be transmitted
- Write logic 0 before writing the
UCSR0A
- TRX0 used for half-duplex communication interfaces (RS-485)
- Set when no new data is in the transmit buffer
- Cleared on a transmit complete interrupt
- Write logic one to clear
- RXC0 indicates unread data present in the receive buffer
- Logic one unread data exist in the receive buffer
- Logic zero receive buffer is empty
- Executes the receive complete interrupt
- Receive complete routine must read buffer to clear flag
- Error flags
FE0,DOR0, andUPE0must be read before the receive buffer- FE0 state of the first stop bit (logic zero when the stop bit was correctly read as ‘1’)
- DOR0 indicates data loss due to a receiver buffer full condition (logic one if serial frames were lost)
- UPE0 indicates that the next frame had an parity error
Transmit
Wait for empty transmit buffer and write 8-bit:
while ( !( UCSR0A & (1<<UDRE0)) ); // wait for empty transmit buffer
UDR0 = data; // read from the receive bufferSimilar with bit 9 in UCSR0B.TXB8
while ( !( UCSR0A & (1<<UDRE0)) );
UCSR0B &= ~(1<<TXB80);
if ( data & 0x0100 )
UCSR0B |= (1<<TXB80);
UDR0 = data;Receive
Receiving Frames with 5 to 8 Data Bits:
- Starts data reception when it detects a valid start bit
- Following bits sampled at the baud rate or XCK0 clock
- First stop bit completes serial frame in receive buffer
Poll RXC receive complete flag, before read of the receive buffer via UDR0
// wait for data to be received
while ( !(UCSR0A & (1<<RXC0)) )
// up to 8-bit receive
data = UDR09-bit receive with UCSR0B.RXB8:
- Read status flags
FE0,DOR0andUPE0first - Read
RXB8before reading the low bits from theUDR0 - Rads all the I/O registers before computation to free the buffer to accept new data as early as possible
unsigned char status, resh, resl;
while ( !(UCSR0A & (1<<RXC0)) )
status = UCSR0A;
resh = UCSR0B;
resl = UDR0;
if ( status & (1<<FE0)|(1<<DOR0)|(1<<UPE0) )
return -1;
resh = (resh >> 1) & 0x01;
return ((resh << 8) | resl);Interrupt
| Bit | UCSR0B | Control and Status Register 0 B |
|---|---|---|
| 7 | RXCIE0 | RX Complete Interrupt Enable |
| 6 | TXCIE0 | TX Complete Interrupt Enable |
| 5 | UDRIE0 | Data Register Empty Interrupt Enable |
Interrupt vectors on Atmega328p (AVR-Libc reference - Library Reference - <avr/interrupt.h>):
| Vector | Description |
|---|---|
| USART_RX_vect | RX Complete |
| USART_TX_vect | TX Complete |
| USART_UDRE_vect | Data Register Empty |
GPIO
General-Purpose Input/Output…
- Pins connect the microcontroller electrically to the outside world:
- Most of a microcontroller’s I/O pins can be configured as an output or an input.
- Special direction register will control if a pin is an input or output.
- A pin with low voltage (ideally 0V) represents logic 0.
- A pin with high voltage (close to supply voltage (VCC)) represents logic 1.
- Protective diodes on every pin should protect the microcontroller in case of over/under voltage.
Ports
I/O pins are usually configured in groups of 8 bit I/O ports. Ports are represented by registers inside the microcontroller:
- Allow programs (firmware) to control the state of pins
- One-to-one correspondence between the pins on the microcontroller and the bits in its registers.
- If configured as input a data register is used to read the state of the pin.
Assembly & high-level language typically includes instructions to manipulate a single pin of a port:
- Otherwise a program need to use a bit mask when reading the entire port.
- Port registers may appear in the same memory map as the processor’s memory (RAM).
- Instructions that operate on RAM will also work with the I/O registers.
Pull Resistors
Internal resistors may create a predictive state (0 or 1) when an in input is read.
- Prevents signal floating if the input signals is switching between 0 and 1.
- A pull-up resistor sets the input near the supply voltage (logic 1).
- A pull-down resistor sets brings the voltage near zero (logic 0).
- Many MCUs have internal pull resistors controlled by a register.
Current Limits
I/O pins can…
- …source (provide positive current) or…
- …sink (provide negative current)
- …up to 40mA per pin (high drive)
- …all I/O lines should not exceed
- …200mA total current
- …which is the limit of the micro-controller
Digital I/O
Arduino Library
D[19:0] GPIO pins:
| Pins | Description |
|---|---|
| 0,1 | RX,TX for serial communication |
| 0-7 | Port D[7:0] |
| 8-13 | Port B[5:0] |
| 13 | Connects to the onboard LED |
| 14-19 | Port C[5:0] (analog input pins 0-5) |
Simple blink example (onboard LED)…
int led = 13;
// the setup routine runs once when you press reset:
void setup() {
// initialize the digital pin as an output.
pinMode(led, OUTPUT);
}
// the loop routine runs over and over again forever:
void loop() {
digitalWrite(led, HIGH); // turn the LED on (HIGH is the voltage level)
delay(1000); // wait for a second
digitalWrite(led, LOW); // turn the LED off by making the voltage LOW
delay(1000); // wait for a second
}Library functions:
- Pin behavior is configured with the pinMode() function
- Pins default to
INPUTmode and are said to be in high-impedance state - Pins configured to
OUTPUTmode are said to be in low-impedance state - The function digitalWrite() sets an output value on pins in OUTPUT mode
- The function digitalRead() reads values from pins in INPUT mode
Digital pins can only have two possible value HIGH or LOW (pin level):
| Mode | Function | State | Description |
|---|---|---|---|
| INPUT | digitalRead() |
HIGH | If the voltage is >= maximum input threshold voltage |
| INPUT | digitalRead() |
LOW | If the voltage is <= minimum input threshold voltage |
| INPUT | digitalWrite() |
HIGH | Enable the internal pull-up resistor, unless driven down by externally |
| OUTPUT | digitalWrite() |
HIGH | Source maximum output voltage/current |
| OUTPUT | digitalWrite() |
LOW | Pin is at 0V, the pin can sink current |
The Atmega chip has pull-up resistors build in accessible via software:
- ….inverts the behavior of input mode!
- …value of the pull-up depends on the micro-controller…
- …(guaranteed to be between 20kΩ and 50kΩ)
pinMode(pin, INPUT_PULLUP);
// this is the same like using
pinMode(pin, INPUT); // set pin to INPUT state, if not already an INPUT
digitalWrite(pin, HIGH); // turn on pullup resistorsAVR Registers
8 Bit bi-direction I/O ports:
- Three ports
PB[7:0],PC[5:0],PD[7:0] - Pins can be configured us input (with/without pull-up) or output (low/high) direction
- All pins have read-modify-write ability and can change direction independently
- Pins have multiple alternate functions driven by the internal peripherals
- Each pin can only have one function assigned at a time
Simple blink example…
/* Include name and addresses of I/O ports */
#include <avr/io.h>
int main(void) {
long i;
DDRB = 1<<5; // PB5/D13 is an output
while(1) {
PORTB = 1<<5; // binary one, aka. LED on
for(i = 0; i < 100000; i++); // sleep
PORTB = 0<<5;
for(i = 0; i < 100000; i++); // sleep
}
}Ports
Names if registers and the individual bits are shown in the ATmega manuals.
The port registers are defined by the following variables:
| Register | Description |
|---|---|
| DDRx | defines the data direction (in/out) |
| PORTx | control the value of a pin |
| PINx | used to read a value of a pin |
- A port is identified by
x(x = B,C,D)DDR[B,C,D] - PUD (Pull Up Disable) bit in the SFIOR Register can be set to disable all pull-ups in all ports.
Pin configuration:
| DDRxn | PORTxn | PUD | I/O | Pull-up | Comment |
|---|---|---|---|---|---|
| 0 | 0 | x | in | no | tri-state (hi-z) |
| 0 | 1 | 0 | in | yes | Pxn sources current (is ext. pulled) |
| 0 | 1 | 1 | in | no | tri-state (hi-z) |
| 1 | 0 | x | out | no | output low (sink) |
| 1 | 1 | x | out | no | output high (source) |
Pins
The port register variables are used as any other variable:
DDRB = 0b00000001
PORTB = 0x0f ; // 0b00001111
PORTC = 1 << 2 // 0b00000100Individual bits can not be read or written in the same way as a full register, but require bitwise operations and masking:
// port manipulation
DDRx |= (1<<PDn); // Set Pin for output
DDRx &= ~(1<<PDn); // Set Pin for input
PORTx |= (1<<PDn); // Set internal pull-up resistor (after setting pin for input)
// digital write
PORTx |= (1<<PDn); // Set Pin High
PORTx &= ~(1<<PDn); // Set Pin Low
// digital read
if (PINx & (1<<PDn));PWM
Pulse-Width Modulation…
- …generates analogue signals (voltage levels) from a digital device
- Still a digital signal with a defined time period between on and off (high/low)
- Generates a square wave instead of a constant voltage
- If the frequency is sufficiently high the output can be adjusted anywhere between 0-100%
- The duty Cycle describes the time in percent (proportion) the output/signal is high over a constant time interval
Disadvantage: Power/energy delivered is not continuous
- If a high frequency is not sufficient use additional passive electronic filters
- Filters smooth the pulse to recover an analog waveform
Common applications:
- Control dimming of RGB LEDs
- Control the direction/angel of a servo motor
- Control the speed of a fan
- Voltage regulators (usually filtered with an inductor & capacitor)
- May be used to encode a message into a pulsing signal to transmit information
Arduino Analog Write…
- …
D[3,5,6,9,10,11]pins with PWN support (marked with~): - …Duty-cycle pulse stream at approx. @490Hz frequency
- …limited to 8bit resolution, values from
0up to255 - …analogWrite(pin,dutyCycle)