
In this tutorial, You will learn How to program the Serial Ports of your Linux System using C Language and the native termios API .
We will then send and receive data from an Microcontroller board like Arduino UNO (Mega) or MSP430 Launchpad connected to your Linux PC Virtual Serial Port.
Here we will be using C language to program the serial port on a Linux Operating system (Ubuntu/ Linux Mint).
For compiling our serial port C codes,We will use the native GCC compiler that is available by default on most Linux systems.
If you are looking for programming serial port using C++, Python, C#, VB.NET, or Java, be sure to explore our detailed tutorials
Serial Ports are nice little interfaces on the PC which helps you to interface your embedded system projects using a minimum number of wires,three to be precise (TX,RX and Ground). One problem with the traditional serial ports is that they are now legacy hardware and are being phased out by the PC manufacturers and most laptops have USB ports only,this problem can be easily solved by using a variety of USB to Serial Converters available in the market, eg USB2SERIAL.
We also make fully isolated DIN Rail Mountable USB to Serial /RS232/RS485 converters that provide full protection from random electrical spikes and Surges,which can be used to safely interface your PC's USB port with Other Serial ,RS232/RS485 devices.
Please note that in this tutorial I am using a USB to Serial Converter based on FT232 from FTDI. You can use any FT232 based board ( other USB converter boards based on different chip sets should work ) or you can buy the one I am using from here.
If you have traditional D sub miniature (DB9) Serial Ports like in the case of some Industrial PC's (shown below)), just identify the relevant pins (RXD, TXD, RTS, DTR and Ground) and continue with the tutorial.

Contents
- Source Codes
- Linux Serial Port Architecture
- Serial Ports under Linux OS
- Programming the Linux Serial Port in C
- Opening and Closing the Serial Port
- Serial Port Access Permissions in Linux
- Configuring the termios structure
- termios members needed for Serial Port Configuration
- c_iflag
- c_cflag
- c_lflag
- Configuring Serial Port Parameters using termios struct
- Setting Serial Port Baud Rate using termios
- Hardware Connections
- Clearing Serial Port IO Buffers
- Reading Data from the Serial Port
- Setting Timeouts in Read Operations
- Arduino Side Code
- Writing data into Serial Port
- Arduino Side Code
- Bidirectional Linux Serial Port Communication in C
- Controlling the RTS and DTR pins of Serial Port
Source codes

Please note that the source codes on the website show only the relevant sections to highlight the process of programming the serial port.
Download the Linux Serial Port Programming Tutorial in C as a Zip file
Browse the Linux Serial Port Programming Tutorial in C on GitHub
Linux Serial Port Architecture
Here is a brief simplified overview of how a Linux system receives data from the external device like Arduino or STM32 development board.The below image shows a simplified diagram of the whole process.

The serial data from the external device enters the UART chip connected to the computer's motherboard or a UART chip on a USB-to-Serial converter.
The serial data is first received and placed into the internal receive FIFO (First In, First Out) buffer of the UART chip. The size of this hardware FIFO buffer varies depending on the UART chip and typically ranges from 256 to 1024 bytes.
The serial port device driver running in the Linux kernel is alerted by the UART chip (typically via an interrupt), and the data from the hardware buffer is then copied into a kernel software buffer, which is part of the TTY subsystem.
The TTY subsystem in Linux is a core component of the kernel responsible for handling text-based input/output devices, including physical or virtual terminals and serial ports (e.g., /dev/ttyS*, /dev/ttyUSB*).
The TTY layer maintains separate ring buffers for input and output data, each typically around 4096 bytes in size. These buffers can be cleared from user space using the tcflush() function.
Our serial port code runs in user space and uses the read() system call to retrieve data from the kernel software buffer. The application then processes the data according to the program's logic.
When we want to send data to the external device, we use the write() system call to place data into the kernel software buffer. The device driver then transfers the data into the UART chipβs transmit FIFO, which ultimately sends it out to the connected external device.
Serial Ports under Linux
Here we will first learn how Linux treats the serial port devices inside its file system.
Linux uses device files to represent hardware devices like serial ports. The /dev directory in Linux is a special virtual filesystem that contains device files, these files represent hardware devices and virtual devices that your system can interact with.All your Serial devices will be listed in the /dev directory
You can view them by typing ( shown in the below image).
# -p flag in the ls command is used to append a forward slash / to directory names in the listing output.
# This makes it easy to distinguish directories from regular files.
ls -p /dev

Identifying Hardware Serial Ports in Linux
Traditional hardware serial ports ( traditional 16550 UART style serial ports) under Linux are named as ttyS* where * can be 1,2,3... etc. for eg ttyS1,ttyS2,ttyS23 ...... etc.They are similar to COM1,COM2 etc under a Windows OS (Windows 10,11).
Most Computers and Laptops in the market no longer has a traditional DB9 Serial Port.If your motherboard supports hardware UART's they may be listed as ttyS* as in the case of some Industrial grade computers.


Now in the above screenshot ,you can see multiple hardware serial port files like ttyS1 to ttyS31 on a Laptop with no hardware based serial ports.
Most of the /dev/ttys* entries in the above screenshot are statically created device nodes or made available by dynamic device management like udev, anticipating possible serial or pseudo-serial devices. These are not actual hardware-backed files unless something opens or uses them.
Now to identify which of the ttyS* corresponds to your hardware serial port run the following command on the terminal.
# use sudo in some systems
dmesg | grep ttyS
if you are getting an output like this
[ 37.531286] serial8250: ttyS0 at I/O 0x3f8 (irq = 4) is a 16550A
it means that ttyS0 is your hardware serial port connected to your computer .
Now if you don't have any hardware serial ports ( like in my case ) the command will not print anything,as shown below.

Checking Hardware Serial Ports using setserial utility
You can also use the setserial utility to get the available serial ports on the Linux system.
Please note that setserial utility only works on traditional serial ports, devices that are compatible with the 8250/16550 UART chipset.
If you use setserial with other chipsets like FT232 it will generate an error "Cannot get serial info: Inappropriate ioctl for device"
You have to install the setserial utility first using apt.
You can get the UART settings of all the available hardware Serial devices on a Linux system using the below command.
sudo setserial -g /dev/ttyS* # -g "Get" current settings

The output shows UART : unknown which means no hardware UART found on the motherboard of my Laptop.All the ttyS* are just place holders.
Now if a real UART hardware device is present and detected by the system then we will get the following output.
/dev/ttyS0, UART: 16550A, Port: 0x03f8, IRQ: 4
Identifying Virtual Serial Ports in Linux
Here we will learn how to identify and use Virtual Serial ports created by USB to Serial Converters and Embedded microcontroller boards like Arduino on a Linux System.
The virtual serial ports on Linux come in a variety of ways as shown below.
/dev/ttyUSB0 -these are for USB to Serial Converters based on FTDI ,CH340 or other chips that uses UART over USB Protocol.These are USB devices pretending to be serial ports, often used for RS-232, TTL, or debugging connections.They need to have drivers installed on the system.
/dev/ttyACM0 - these are common for microcontrollers that implement USB natively, like Arduino Leonardo, Micro, Due,MSP430 Launchpad, STM32 boards with native USB controllers.Appears when the device supports the CDC-ACM protocol.
/dev/ttyAMA0 - appears when you are using a Serial port on ARM-based boards (like Raspberry Pi UART).
using dmesg to identify ports
Best way to get the name of the Virtual Serial port is to connect the device to your Linux installation and run a dmesg command as shown below.
sudo dmesg | tail
here we are running dmesg to get the messages from the kernel Ring Buffer and pipes to the tail command so the last 10 lines are displayed on the terminal.
Here is the output after connecting an Arduino .

or you can use
sudo dmesg | grep tty

Another place where you can see the attached serial devices is the /dev/serial/by-id folder.

Here is an example on Ubuntu Showing MSP430Launchpad and a USB to serial converter attached to Linux Serial Port.

Programming the Linux Serial Port in C
In this tutorial i am going to use C language to program the Serial port on a Linux System using GCC Compiler,
To perform serial I/O under Linux we are going to use the termios API.
What is termios API
The termios API in Unix-like systems (including Linux and macOS) provides an interface for controlling asynchronous communications ports, such as terminals and serial ports. It is commonly used in POSIX-compliant systems for low-level terminal I/O configuration.
termios API supports two modes of accessing the serial ports.
1. Canonical Mode
2. Non-Canonical Mode (Raw Mode)
Canonical mode is the default mode and is used for accessing terminals and stuff.
For our tutorial we are going to use the second mode called the non canonical mode.In non-canonical mode, input is processed immediately, character by character, or in chunks, rather than waiting for a newline (\n).
Displaying Available Serial Ports in C
Here we will use a C Program to display available serial ports on your Linux system on the terminal so the user can choose which port to select.
We will run the ls command using the system() function provided by stdlib
// Program to run system commands using c program
// Program will list the serial ports
#include <stdlib.h>
void main()
{
system("ls /dev/ttyUSB* /dev/ttyACM* 2>/dev/null"); // running ls command to list serial ports
}
Here we are running the ls command inside with wild cards.
The 2>/dev/null part hides errors like "No such file or directory" when no matching devices are found.
The 2 refers to file descriptor 2, which is the standard error (stderr) stream in Unix-like operating systems.We are redirecting errors to /dev/null so they don't appear on the terminal.

Opening and Closing the Serial Port
Opening a serial port in Linux is accomplished by using the open() system call and closing the serial port is done using the close() system call.
Here is a simple code to open a connection to the Linux Serial Port using C and close it after some time.
Replace /dev/ttyACM0 with the name of your Serial Port before running the code.
/*
Basic Code to Open a Serial port on Linux using C and termios API
(c) www.xanthium.in 2025
serial_open.c
*/
#include <stdio.h>
#include <fcntl.h> /* file open flags and open() */
#include <termios.h>
#include <unistd.h>
int main()
{
// Replace /dev/ttyACM0 with the name of your Serial Port
int fd = open("/dev/ttyACM0", O_RDWR | O_NOCTTY); //open a connection to serialport
if (fd == -1)
{
perror("Failed to open serial port"); /* to print system error messages */
return 1;
}
else
{
printf("Connection to Port Opened fd = %d \n",fd);
}
close(fd); /* Close the file descriptor*/
}
Here is the explanation of the Serial port Open code.
The open() system call takes two arguments ,
- name of the file to be opened (here serial port )
- and the various parameters associated with it.
open() system call returns a -1 on failure and sets the global variable errno to indicate the error.
open() system call returns a positive integer on success.
int fd = open("/dev/ttyACM0", O_RDWR | O_NOCTTY); //open a connection to serialport
The first argument to the open() system call is the name of the serial port to be opened,Here We are giving the name as "/dev/ttyACM0". Please note that the name of the serial port may be different on your system.Use the correct name while opening the port.
Second argument
O_RDWR means that the port is opened for both reading and writing.
- O_NOCTTY means that no terminal will control the process opening the serial port.
Here if there is an issue with opening the serial port open() returns a -1 which is used to check and print the error message using perror()
if (fd == -1)
{
perror("Failed to open serial port"); /* to print system error messages */
return 1;
}
After a serial port is opened it should be closed by using the close() system call. close() takes a single argument,the file descriptor fd which we have earlier used to open the serial port using open() system call.Like this
close(fd); /* Close the file descriptor*/
Save the above code to a text editor with file extension .c .You can compile the code using gcc .
gcc serial_open.c -o serial_open
and run the code using
./serial_open

Please make sure your hardware (Arduino or USB to Serial Converter) is connected before executing the binary.
if you are getting Serial port permission denied error in Linux like the one shown below,
You will have to set up the permission for groups as shown below.
Serial Port Access Permissions in Linux
If you run the above code and is getting the following error " Access to ttyUSB0 or ttyACM0 access denied" or " Failed to open serial port :permission denied" error as shown below.

You may need to add the user to groups that have permission to access to the Serial Port.
To access the serial port ,the user must be part of 2 groups
- tty
- dialout
You can use the usermod command to add yourself to these two groups.
Please note that you should have permission to run the sudo command (part of the Sudo group in Ubuntu) or part of the wheel group in Centos/RHEL/Rocky Linux.
Adding a user to tty and dialout groups for serial port access in Linux .
sudo usermod -a -G tty $USER
sudo usermod -a -G dialout $USER
Here $USER variable is a standard environment variable in Unix-like operating systems (such as Linux and macOS) which contains the username of the currently logged-in user.

The -a makes sure that you are appending the user to the groups .
if -a is missing you will get unsubscribed from all other groups except tty and dialout.
After the commands are run,
Logoff from your account and then log back in so that changes are saved.
Here is an example running on Ubuntu


Configuring the termios structure
Now that weβve successfully opened the serial port in Linux using the open() system call, the next step is to configure its settings.
This includes setting the
- baud rate,
- parity,
- number of start and stop bits,
- and the number of data bits
- using the termios structure.
These configurations are essential to ensure proper serial communication with the connected Arduino UNO from our Linux System (Linux Mint/Ubuntu/Fedora).
In Linux, the termios structure is part of the POSIX API used to configure terminal I/O settings. When working with serial ports (like communicating with an Arduino), termios allows you to control how data is transmitted and received by setting parameters such as baud rate, character size, parity, stop bits, and more.
Itβs defined in the <termios.h> header and looks something like this
struct termios
{
tcflag_t c_iflag; /* input mode flags */
tcflag_t c_oflag; /* output mode flags */
tcflag_t c_cflag; /* control mode flags */
tcflag_t c_lflag; /* local mode flags */
cc_t c_line; /* line discipline */
cc_t c_cc[NCCS]; /* control characters */
};
Now first thing to do is to declare a structure of type termios,make sure that you have included the header file <termios.h>
struct termios serial_port_settings;
Now to configure the termios structure according to our needs we use two functions,
tcgetattr()
tcsetattr().
tcgetattr() gets the current terminal settings (I/O configuration) for a device (often a serial port or terminal).
It takes two arguments,
the file descriptor fd corresponding to the serial port we have just opened
the address of the structure we just declared.
int tcgetattr(int fd, struct termios *termios_p);
So in our case it will be
tcgetattr(fd, &serial_port_settings);
After getting the current serial port settings we are going to change it suit our needs ,
to do that we will use the tcsetattr() function to update the structure with modified values.

Here is a example code for updating the termios structure,full code is available on our GitHub repo.
tcgetattr(fd, &serial_port_settings); // get the serial port settings from the termios structure
serial_port_settings.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG); // Enable NON CANONICAL Mode
//change setting 1 here
//change setting 2 here
tcsetattr(fd,TCSANOW,&serial_port_settings); // update new settings to termios structure,
// TCSANOW tells to make the changes now without waiting
termios members needed for Serial Port Configuration
The termios structure controls many I/O settings. However, for controlling the serial port on Linux, we only need to know three members of the structure; the rest can be ignored.
struct termios
{
tcflag_t c_iflag; /* input mode flags */
tcflag_t c_oflag; /* */
tcflag_t c_cflag; /* control mode flags */
tcflag_t c_lflag; /* local mode flags */
cc_t c_line;
cc_t c_cc[NCCS];
};
c_iflag
Here tcflag_t c_iflag is used to control software based flow control during Serial Communication.
Software flow control uses in-band special characters like XON (0x11, Ctrl-Q) and XOFF (0x13, Ctrl-S) to pause/resume transmission.
Disabling these flags prevents the terminal driver from interpreting Ctrl-S, Ctrl-Q, or any other character as flow control.
The Flags are named IXON,IXOFF, IXANY which we will clear in order to disable software based flow control
- IXON Disables transmit flow control
- IXOFF Disables receive flow control
- IXANY Disables the feature that allows any character to restart output
c_cflag
The tcflag_t c_cflag field in the termios structure controls hardware-related serial port behavior, such as:
- Character size (how many bits per character)
- Parity checking (used for error detection)
- Number of stop bits
- Whether the receiver is enabled
- Whether modem control lines are used
This field is especially important when configuring serial ports or working with raw terminal I/O.
- CSIZE Bitmask for character size (use with CS5, CS6, CS7, CS8)
- CS5 5-bit characters
- CS6 6-bit characters
- CS7 7-bit characters
- CS8 8-bit characters (most common)
- CSTOPB Use 2 stop bits instead of 1
- CREAD Enable receiver (needed to receive input)
- PARENB Enable parity generation and checking
- PARODD Use odd parity (if PARENB is set); otherwise even parity
c_lflag
c_lflag controls local modes (e.g., canonical mode, echo, signals).
c_lflag is also used to select between canonical or non canonical mode by clearing the ICANON Flag
Configuring Serial Port Parameters using termios struct
Our plan is to configure the serial port in the 8N1 format for communicating with the connected Arduino UNO which means
Data bits = 8,
Parity = None and
No of Stop Bits = 1
To SET and Clear the bits we will be using C Bit wise operators.
For example
//Bit set/clear demo in C using BIT wise operators
serial_port_settings.c_cflag &= ~(CRTSCTS); //Clear Flag CRTSCTS,
serial_port_settings.c_cflag |= (CRTSCTS); //SET Flag CRTSCTS,
Now here we will set all the required parameters like Parity,Number of stop bits,Data bit size etc needed for serial communication with Arduino in the termios struct using C language.
We will be clearing some flags and setting some flags (c_iflag ,c_cflag) inside the termios struct to configure your Linux PC for Serial Communication.
Here is the partial code for it .
tcgetattr(fd, &serial_port_settings); // get the serial port settings from the termios structure
serial_port_settings.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG); // Enable NON CANONICAL Mode for Serial Port Comm
serial_port_settings.c_iflag &= ~(IXON | IXOFF | IXANY); // Turn OFF software based flow control (XON/XOFF).
serial_port_settings.c_cflag |= CREAD | CLOCAL; // Turn ON the receiver of the serial port (CREAD)
serial_port_settings.c_cflag &= ~CRTSCTS; // Turn OFF Hardware based flow control RTS/CTS
// Set 8N1 (8 bits, no parity, 1 stop bit)
serial_port_settings.c_cflag &= ~PARENB; // No parity
serial_port_settings.c_cflag &= ~CSTOPB; // One stop bit
serial_port_settings.c_cflag &= ~CSIZE;
serial_port_settings.c_cflag |= CS8; // 8 bits
tcsetattr(fd,TCSANOW,&serial_port_settings); // update new settings to termios structure,
// TCSANOW tells to make the changes now without waiting
First we get the termios struct using tcgetattr() ,So we can modify it
All Serial Communications happens in the NON CANONICAL Mode,So first we put the serial port in that mode using.
serial_port_settings.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG); // Enable NON CANONICAL Mode for Serial Port Comm
Here we are clearing the ICANON flag to put it in NON CANONICAL Mode.
Clearing ECHO disables echo, so typed characters are not shown.
- When set, the erase character (usually backspace) erases the last character on the screen.Clearing ECHOE disables this special erase echo behaviour.
- Certain input characters (like Ctrl-C and Ctrl-Z) are interpreted as signals (SIGINT, SIGTSTP).Clearing ISIG disables signal generation, so these characters are sent as normal input instead of interrupting the program.
We then turn OFF software based flow control
serial_port_settings.c_iflag &= ~(IXON | IXOFF | IXANY); // Turn OFF software based flow control (XON/XOFF).
We enable the receiver here
serial_port_settings.c_cflag |= CREAD | CLOCAL; // Turn ON the receiver of the serial port (CREAD)
Setting CREAD , Enables the receiver. This means the serial port can receive incoming data.
Setting CLOCAL tells the system to ignore modem control lines (like carrier detect). This prevents the serial port from being affected by modem status signals, making it suitable for direct device connections like Arduino.
Now we configure Parity,Stop Bits and number of data bits ,Our aim is to configure the serial port in 8N1 format .(8 Data bits,No Parity,1 Stop bit)
serial_port_settings.c_cflag &= ~PARENB; // Disable parity bit (No parity)
Here we clear the Parity Enable bit PARENB. So we will now get NO Parity
Please note that you can also use EVEN or ODD Parity if you want to by enabling the parity bit and setting the required parity as shown below.
Set EVEN Parity
serial_port_settings.c_cflag |= PARENB; // Enable parity
serial_port_settings.c_cflag &= ~PARODD; // Use even parity
Set ODD Parity
serial_port_settings.c_cflag |= PARENB; // Enable parity
serial_port_settings.c_cflag |= PARODD; // Use odd parity
serial_port_settings.c_cflag &= ~CSTOPB; //Clears the CSTOPB bit, uses 1 stop bit
This line Clears the CSTOPB bit so that our code will uses 1 stop bit (1 in 8N1). If CSTOPB were set, it would use 2 stop bits.
serial_port_settings.c_cflag &= ~CSIZE; // Clear current character size mask
serial_port_settings.c_cflag |= CS8; // Set character size to 8 bits
Here we set the number of data bits used to encode the character send to the Arduino from PC .
First, We clear the size bits to prepare for setting a new size (~CSIZE) .Then we set character size to 8 bits using CS8.
termios also support other data bit sizes like CS5 (5 data bits), CS6 (6 data bits) and CS7 ( 7 data bits).These are not used generally.
Finally we update the termios struct using
tcsetattr(fd,TCSANOW,&serial_port_settings); // update new settings to termios structure,
// TCSANOW tells to make the changes now without waiting
Here
fd is the file descriptor corresponding to the serial port we have just opened
TCSANOW is a flag that controls when the settings take effect.Here it means to apply the changes immediately without waiting
&serial_port_settings - Pointer to a struct termios that contains the desired settings.
Setting Serial Port Baud Rate using termios
Here we are going to set the baud rate (speed) for communicating with an Arduino from a Linux PC using termios API and C .
In Linux ,there is an option to set different read and write speeds but it is recommended to set the same speed for both read and write.
The Baudrate in Linux is set using two functions,
cfsetispeed() for setting the input speed or read speed and
cfsetospeed() for setting the output speed or write speed.
Now let's set the speed for both reading and writing at 9600 bps because we are using 8N1 .
You have to call tcgetattr() before setting the baudrate.
tcgetattr(fd, &serial_port_settings); // get the serial port settings from the termios structure
cfsetispeed(&serial_port_settings,B9600);
cfsetospeed(&serial_port_settings,B9600);
tcsetattr(fd,TCSANOW,&serial_port_settings); // update new settings to termios structure,
You can use other standard baud rates like 4800,19200,38400 etc ,All Baudrate constants have to be prefixed with a 'B' like B4800 , B19200 etc .
Please note that the MSP430 microcontroller and Arduino code provided (microcontroller side) uses 9600bps 8N1 format for communicating with the Linux PC using Serial Port .
If you want to read the current baud rate from the termios structure ,You can use the following functions to do that.
cfgetispeed() to get the input baud rate
cfgetospeed() to get the output baud rate
speed_t baud = cfgetispeed(const struct termios *termios_p);
// Pointer to a termios structure obtained using tcgetattr()
// returns a value of type speed_t, which is a macro representing a baud rate
Before calling this you will have to call the tcgetattr() function.
Here is a code snippet in C to get current baud rate from termios structure.
tcgetattr(fd, &serial_port_settings); // get the serial port settings from the termios structure
speed_t input_baudrate = cfgetispeed(&serial_port_settings); //Get input baud rate
speed_t output_baudrate = cfgetospeed(&serial_port_settings); //Get output baud rate
//use switch to compare and get correct baudrate in integer
switch(input_baudrate)
{
case B4800: printf("input_baudrate = 4800\n");break;
case B9600: printf("input_baudrate = 9600\n");break;
case B19200: printf("input_baudrate = 19200\n");break;
//add other cases
}
close(fd); /* Close the file descriptor*/
Hardware Connections
Here we will learn to connect an Arduino (ATmega328P) or a MSP430 Microcontroller with a Linux PC for Serial communication using C Language.
Connecting a Bare Microcontroller UART to Linux PC
Here is a simple block diagram for connecting a bare microcontroller like MSP430 or ATmega328P with a Linux PC for Serial Communication using Virtual Serial Port.

The PC is connected to the microcontroller board using a null modem cable.The RX of the PC (serial port) is connected to the TX of the Micro controller and vice versa.The Grounds of PC and microcontroller are connected together.
Here my PC do not have a hardware DB9 serial port(9 pin),So i am using a FTDI based USB to Serial converter called USB2SERIAL which converts the USB signals to TTL compatible serial outputs (RXD and TXD).

USB2SERIAL also offers selectable 3V/5V TTL outputs for interfacing to 3.3V logic microcontrollers like MSP430 .When you are using MSP430 Micro controller change the logic level voltage to 3V on the USB2SERIAL board.
Please noter that if you are using a DB9 RS232 SerialPort of your PC ,you will have to build a RS232 signal level converter at the microcontroller side to decode the RS232 signal. Connecting the RS232 Lines from the PC directly to microcontroller UART directly will damage the chip.
Connecting an Arduino to the Linux PC

When you are connecting the Arduino to the Linux PC ,there is no need to use a USB to Serial Converter as the board has a build in ATmega32u4 chip which does the conversion as shown in the above figure.Just connect the Arduino and find out the corresponding serial port number.
Clearing Serial Port IO Buffers
You can use the function tcflush() to clear the IO Buffers of the Linux Serial Port.This is used to prevent our user program from sending or receiving garbage values to the device connected to the serial port,in our case an Arduino.
Here is a brief overview of the Linux Serial Port Buffer system,

Here the serial data coming from the outside (RX/TX/GND signals ) are received by the hardware buffer of either the UART chip inside the PC or the Serial to USB converter chip like FT232.
The hardware UART buffers are FIFO queue's that has a size between 256 bytes to 1024 bytes depending upon the chip model.
A device driver copies the data from UART chip into the internal kernel software ring buffer which is a part of the TTY subsystem.The size of the kernel software buffer is not fixed and is approximately 4096 bytes.
The user space Code (your code) then uses read() / write( ) system calls to read and write into the Kernel Buffer to send and receive data from the external serial device.
When you use the tcflush() function it clears the internal Kernel Software buffer.
Here is the basic syntax of the tcflush() function
int tcflush(int fd, int queue_selector);
//queue_selector refers to input queue ,output queue or both
- TCIFLUSH Flush input buffer of Kernel RX buffer
- TCOFLUSH Flush output buffer of Kernel TX buffer
- TCIOFLUSH Flush both input and output buffers ( Both RX and TX buffers)
These affect the TTY buffers, not the hardware FIFOs directly.However, drivers may implicitly reset or flush hardware buffers when kernel buffers are flushed,but that's driver-dependent and not guaranteed.
Basic code for clearing the Serial port io buffers in Linux
#include <termios.h>
#include <unistd.h>
#include <fcntl.h>
int main()
{
int fd = open("/dev/ttyUSB0", O_RDWR | O_NOCTTY);
tcflush(fd, TCIOFLUSH); // Flush both RX and TX
close(fd);
}
Reading Data from the Serial Port
In this section ,we will learn how to read data from a Linux serial port using C language.
Here ,we have an Arduino connected to a Linux Computer (Ubuntu/Linux Mint or Fedora) through the Virtual Serial Port through USB cable as shown below.

The Arduino board sends a string of characters to the Linux PC's Serial Port which are read by the c program running on the Linux computer using read() system call and the text is displayed on the terminal.
At first i will explain the PC side C code to receive data from Arduino.
Setting Timeouts in Read Operations
When we are receiving data from an external device like Arduino through serial port,The program may wait indefinitely for the data to come .To prevent this we need to specify time outs in our code which makes the read() call return after the specified amount of time have elapsed.
We also will specify a minimum number of bytes to be read by the read() call before returning.
For that we have to add the following lines to our code .
tcgetattr(fd, &serial_port_settings); // get the serial port settings
// configure other settings here
serial_port_settings.c_cc[VMIN] = 20; /* Read at least 20 characters */
serial_port_settings.c_cc[VTIME] = 10; /* Wait for 10 *100ms = 1 second ,measured in increments of 100ms */
tcsetattr(fd,TCSANOW,&serial_port_settings);
Here ,
c_cc[VMIN] = 20; tells the serial port driver that the read() call should wait until at least 20 bytes are received before returning.If fewer than 20 bytes arrive, read() will block (wait) until either 20 bytes are received or a timeout occurs.Value 20 is arbitrary as it suits in my case.
c_cc[VTIME] = 10; This sets the timeout value for the read() operation.the value is in tenths of a second (100 milliseconds).So, 10 means 1 second (10 Γ 100ms).The timer starts after the first byte is received. If 20 bytes are not received within 1 second after the first byte, read() will return with however many bytes have arrived.
You can clear the Serial Port IO buffer using tcflush() function to prevent your code from reading in garbage values.
/* Flush both input and output buffers to clear out garbage values */
if (tcflush(fd, TCIOFLUSH) != 0)
{
perror("tcflush");
}
After which we use the read system call to read data from serial port buffer.
Basic syntax of the read() call is shown below.
ssize_t no_of_bytes = read(int fd, void *buffer, size_t count);
Here
fd - is the File descriptor (returned by open() )
buffer - Pointer to a buffer where the read data will be stored
count - Maximum number of bytes to read
no_of_bytes - read() returns the number of bytes read from the serial port on success or -1 in case of error.
Now we will use the read() function to get data from the serial port using below code.
//partial code
//fd file descriptor to serial port
char serial_read_buffer[100] = {}; // Data read from port stored in this array
int received_bytes = read(fd,serial_read_buffer, sizeof(serial_read_buffer)-1); //reading from serial port.
printf("Bytes Received = %d ", received_bytes);
printf("Data Received = %s ", serial_read_buffer);
Here,
fd - the file descriptor for the serial port.
serial_read_buffer- where the read bytes will be stored.
sizeof(serial_read_buffer)-1 reads up to 99 bytes (leaving space for a null terminator if you want to treat the buffer as a string).
Using this we will write a small skeleton C code to read data send from the Arduino.Code is for illustration purposes only and lacks error checking.
Please use the full code from our Github Repo
//Skeleton code for reading from serial port in C using termios.
//Full code available in github.
//skeleton-data-receive-serialport.c
#include <fcntl.h> /* file open flags and open() */
#include <termios.h>
#include <unistd.h> /* close() */
#include <stdio.h>
#include <stdlib.h>
int main()
{
struct termios serial_port_settings;
char serial_read_buffer[100] = {}; //Data read from port stored in this array
int fd = open("/dev/ttyACM0", O_RDWR | O_NOCTTY); //open a connection to serialport
sleep(3); // Delay for 3 seconds,for Arduino to get stabilized,
// Opening the port resets the Arduino
int status = tcgetattr(fd, &serial_port_settings); // get the serial port settings from the termios structure
/***************** Configure the Baudrate *******************/
cfsetispeed(&serial_port_settings,B9600); //Set input Baudrate
cfsetospeed(&serial_port_settings,B9600); //Set output Baudrate
/***************** Configure the termios structure ************************/
serial_port_settings.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG); // Enable NON CANONICAL Mode for Serial Port Comm
serial_port_settings.c_iflag &= ~(IXON | IXOFF | IXANY); // Turn OFF software based flow control (XON/XOFF).
serial_port_settings.c_cflag &= ~CRTSCTS; // Turn OFF Hardware based flow control RTS/CTS
serial_port_settings.c_cflag |= CREAD | CLOCAL; // Turn ON the receiver of the serial port (CREAD)
// Set 8N1 (8 bits, no parity, 1 stop bit)
serial_port_settings.c_cflag &= ~PARENB; // No parity
serial_port_settings.c_cflag &= ~CSTOPB; // One stop bit
serial_port_settings.c_cflag &= ~CSIZE;
serial_port_settings.c_cflag |= CS8; // 8 bits
serial_port_settings.c_oflag &= ~OPOST;/*No Output Processing*/
serial_port_settings.c_cc[VMIN] = 20; /* Read at least 20 characters */
serial_port_settings.c_cc[VTIME] = 10; /* Wait for 10 *100ms = 1 second ,measured in increments of 100ms */
status = tcsetattr(fd,TCSANOW,&serial_port_settings); // update new settings to termios structure,
// TCSANOW tells to make the changes now without waiting
/* Flush both input and output buffers to clear out garbage values */
if (tcflush(fd, TCIOFLUSH) != 0)
{
perror("tcflush");
}
int received_bytes = read(fd,serial_read_buffer, sizeof(serial_read_buffer)-1);
printf("\n\nBytes Received from Serial Port = %d ",received_bytes);
printf("\n\nData Received from Serial Port = %s\n",serial_read_buffer );
close(fd); /* Close the file descriptor*/
}
Arduino Side Code
Before you run the C code, Download the below code to your Arduino board.
//Code is available on our GitHub
//Arduino side Code
void setup()
{
Serial.begin(9600); // Start serial communication at 9600 baud
while (!Serial) { ; } // Wait for serial port to connect (for Leonardo/Micro/Zero)
}
void loop()
{
Serial.println("Hello from Arduino!"); // Send message to PC
delay(1000); // Wait for 1 second
}
The Arduino Code sends the text string "Hello from Arduino!" every 1 second to the Linux PC.
Make sure that baud rates are same on both ends.Code is available on our GitHub Repo ,Link above
Now we will compile and run the C Code on Linux system to Receive Data from Arduino.Here i will be using the full code from our Repo.

Writing data into Serial Port
Before writing to the Serial Port,make sure that you have the correct permissions.
Here we will learn how to write into a Linux serial port using C Language and transmit some data into the connected Arduino.
Writing data to serial port is accomplished using the write() system call provided by the Linux API.
The write() system call in Linux and Unix is used to write data from a buffer (in memory) to a file descriptor ,In our case file descriptor of the opened serial port.
Here is the basic syntax of write ()
write(int fd, const void *buffer, size_t count);
Arguments passed onto write () are
fd ( File descriptor) - integer that refers to an open file or serial port (returned by open() or similar).
buffer - Pointer to the buffer in memory containing the data to write.
count - Number of bytes to write from the buffer.
write () call Returns the number of bytes actually written, on success or Returns -1 if there is an error, and sets errno accordingly.
Now we will use some write() system call to send character 'A' to Arduino using the below code snippet.
/********* Write characters to the Serial Port using write()***************/
char value_to_send = 'A'; /* single quotes,stores the ASCII value of A (65)*/
int bytes_written = write(fd,&value_to_send,sizeof(value_to_send)); // Write data to Serial port
// fd file descriptor of opened serialport
On the Arduino side,
you can receive the data and use a switch statement to perform specific actions on receiving specific characters like send back an acknowledgement or light up an LED.
You need to download the below Arduino Code to your Board before running C serial port code.
//Arduino code for receiving characters and performing specific actions using switch()
void setup()
{
Serial.begin(9600); // Start serial communication at 9600 baud
while (!Serial) { ; } // Wait for serial port to connect (for Leonardo/Micro/Zero)
}
void loop()
{
if (Serial.available() > 0) //Check if serial buffer has data.
{
char ReceivedChar = Serial.read();//Read data in the Buffer
switch(ReceivedChar)
{
case 'A' : Serial.println("Character A Received OK");break;
case 'B' : Serial.println("Character B Received OK");break;
case 'C' : Serial.println("Character C Received OK");break;
default : Serial.println("Invalid Character Received");
}
delay(500);
}//end of if()
}//end of loop()
Bidirectional Linux Serial Port Communication in C
In the previous sections, we learned to read and write into the serial port of a Linux system using C.
Here we will combine both these to create a bidirectional serial communication program that will send data to an Arduino connected to the serial port of the Linux computer.
Arduino receives the data and echo's it back which is then read by the c program running on the computer side and displayed on the terminal.

Here is the basic steps we are going to do to enable bi-directional communication with Arduino from Linux system.
Open the connection to serial port
Configure termios structure,set all Parameters
Use write() system call to send Character A
Wait for Arduino to send back acknowledge using read() till timeout expires
display acknowledgement on terminal
and here is the simplified code to do that. Full code is available on the GitHub Repo (link above)
/*
Basic Code for Bi Directional Serial Communication between Arduino and Linux PC using C language and termios api
Linux PC sends a character 'A' to Arduino using serial port
Arduino Receives character and echoes back a reply "Character A Received OK"
Please Remember to change Serial Port Name Before Running the Code.
(c) wwww.xanthium.in (2025)
*/
#include <fcntl.h> /* file open flags and open() */
#include <termios.h>
#include <unistd.h>
#include <stdio.h>
int main()
{
struct termios serial_port_settings;
int fd = open("/dev/ttyACM0", O_RDWR | O_NOCTTY); //open a connection to serialport
if (fd == -1)
{
perror("Failed to open serial port"); /* to print system error messages */
return 1;
}
else
{
printf("Connection to Port Opened fd = %d \n",fd);
}
sleep(3); // Delay for 3 seconds,for Arduino to get stabilized,
// Opening the port resets the Arduino
tcgetattr(fd, &serial_port_settings); // get the serial port settings from the termios structure
/***************** Configure the Baudrate *******************/
cfsetispeed(&serial_port_settings,B9600); //Set input Baudrate
cfsetospeed(&serial_port_settings,B9600); //Set output Baudrate
/***************** Configure the termios structure ************************/
serial_port_settings.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG); // Enable NON CANONICAL Mode for Serial Port Comm
serial_port_settings.c_iflag &= ~(IXON | IXOFF | IXANY); // Turn OFF software based flow control (XON/XOFF).
serial_port_settings.c_cflag |= CREAD | CLOCAL; // Turn ON the receiver of the serial port (CREAD)
serial_port_settings.c_cflag &= ~CRTSCTS; // Turn OFF Hardware based flow control RTS/CTS
// Set 8N1 (8 bits, no parity, 1 stop bit)
serial_port_settings.c_cflag &= ~PARENB; // No parity
serial_port_settings.c_cflag &= ~CSTOPB; // One stop bit
serial_port_settings.c_cflag &= ~CSIZE;
serial_port_settings.c_cflag |= CS8; // 8 bits
serial_port_settings.c_oflag &= ~OPOST;/*No Output Processing*/
serial_port_settings.c_cc[VMIN] = 25; /* Read at least 25 characters */
serial_port_settings.c_cc[VTIME] = 10; /* Wait for 10 *100ms = 1 second ,measured in increments of 100ms */
tcsetattr(fd,TCSANOW,&serial_port_settings); // update new settings to termios structure,
// TCSANOW tells to make the changes now without waiting
/**/
/* Flush both input and output buffers to clear out garbage values */
if (tcflush(fd, TCIOFLUSH) != 0)
{
perror("tcflush");
}
/********* Write characters to the Serial Port using write()***************/
char value_to_send = 'A'; /* single quotes,stores the ASCII value of A (65)*/
int bytes_written = write(fd,&value_to_send,sizeof(value_to_send)); //Write data to Serial port
printf("\nCharacter Send = %c" ,value_to_send);
printf("\nNumber of Bytes Send = %d" ,bytes_written);
/********* Read characters from Serial Port send by Arduino using read() ************/
char serial_read_buffer[100] = {}; //Data read from port stored in this array
int received_bytes = read(fd,serial_read_buffer, sizeof(serial_read_buffer)-1); //read data from the port
printf("\n\nBytes Received from Serial Port = %d ",received_bytes);
printf("\n\nData Received from Serial Port = %s\n",serial_read_buffer );
close(fd); /* Close the file descriptor*/
}
Now i will be running the full code from repo below. It has a lot of verbose output for the user.
Please download the Arduino Code from the repo before running it.

- Log in to post comments