UART serial communication experiment based on Raspberry Pi 4B and STM32 (code open source)

Preface: This article is to teach the UART communication between Raspberry Pi 4B and STM32 step by step. This project uses Raspberry Pi 4B and  STM32  for serial communication to transmit data to each other. This blog also provides target detection data linkage based on YOLOv5-Lite , that is, the information detected by Raspberry Pi 4B is sent to STM32 , and various requirements can be controlled through this information. The linkage between Raspberry Pi 4B and STM32 is a very common embedded architecture system. Usually Raspberry Pi 4B is responsible for computationally intensive tasks ( such as target detection, laser radar, etc. ), and STM32 is responsible for control tasks. This architecture is also currently Mainstream intelligent hardware processing framework! ( There is code open source at the end of the article! )

Hardware physical map:

Renderings:

1. Raspberry Pi 4B serial port

1.1 Pins of Raspberry Pi 4B

Pin diagram of Raspberry Pi 4B:

As a small computer, Raspberry Pi 4B provides a large number of additional Pins suitable for embedded daily development. In this experiment, we need to realize the UART communication between Raspberry Pi 4B and STM32F103C8T6!

Supplementary note:

As the host computer, Raspberry Pi 4B is responsible for tasks with a large amount of calculation ( such as target detection, lidar, etc. ), and STM32 is responsible for control-oriented tasks. This system framework is one of the mainstream artificial intelligence embedded genres, and now most of the smart cars, smart aircraft, and smart robotic arms use this set of frameworks!

Advantages of this framework:

This framework isolates the control task from the calculation task, realizes the specialization of each CPU, and improves the stability of the system (to facilitate the expansion or maintenance of later tasks). At the same time, although the computing power of STM32 is far weaker than that of Raspberry Pi 4B, its GPIO control ability is stronger than that of Raspberry Pi, that is, it has inherent control advantages. Therefore, the framework is to give full play to their respective expertise!

Common communication methods between Raspberry Pi 4B and STM32:

(1), UART , (2), SPI, (3), I2C (this project uses Serial)

1.2 Install and use Serial on Raspberry Pi 4B

Pin connection:

According to the Pin pin diagram of Raspberry Pi 4B above, the two pins of GPIO14 (TXD) and  GPIO15 (RXD) are respectively connected to the pins of PA10 (RXD) and PA10 (RXD) of STM32F103C8T6 ( cross connection )

1.2.1 install serial

Enter in the terminal: sudo apt-get install serial

1.2.2 Open the Raspberry Pi 4B serial port

Enter in the terminal: sudo raspi-config to open the interface settings

 Interfacing Options→serial→No→Yes

Enter in the terminal: ls -al /dev/view device

1.2.3 Modify the serial port mapping relationship

Enter in the terminal: sudo nano /boot/config.txt

Add dtoverlay=pi3-miniuart-bit to the last line

Restart the Raspberry Pi 4B, then terminal input: ls -la /dev/view device

1.2.4 Modify the configuration file

Enter in the terminal: sudo nano /boot/cmdline.txt

Modify the content of the cmdline.txt file as follows:

dwc_otg.lpm_enable=0 console=tty1 root=/dev/mmcblk0p2 rootfstype=ext4 elevator=deadline rootwait

2. Install minicom and Raspberry Pi 4B test

2.1 minicom installation

minicom is a serial port debugging tool for Linux/Raspberry Pi 4B platform, which is equivalent to the serial port debugging assistant on Windows . At this time, minicom needs to be installed first ;

sudo apt-get install minicom

Enter in the terminal: minicom -D /dev/ttyAMA0

If you want to exit the minicom software, first press CTRL+A and then press Z to pop up the menu, press 0 to exit, and then you can close it directly.

2.2 Raspberry Pi 4B communication test

We use the XCOM serial port debugging assistant to test whether the Raspberry Pi 4B can communicate normally with UART!

Use the USB-TTL module to cross-connect the UART pins of the Raspberry Pi 4B;

★Special note: The VCC and GND of the USB-TTL module must be connected to the corresponding pins of the Raspberry Pi 4B, otherwise the port may output garbled characters due to the unbalanced current!

We enter Hi IKUN in the minicom red box area in the figure below! After the words, you can see that the string has been successfully sent to the PC at the XCOM port ;

In the same way, after the XCOM port sends  the word Hi My Brother , the information can be successfully received in the minicom red frame area of ​​the Raspberry Pi 4B  !

When the above operations are successfully completed, it means that we have successfully configured the UART function of the Raspberry Pi 4B! After that, you can try to communicate with STM32 (send data to XCOM not only through minicom, but also through python and other codes)!

3. Communication between Raspberry Pi 4B and STM32

The STM32 code is actually a simple UART serial communication code, but there are actually many pitfalls! ! ! The author found that most of the bloggers did not explain the pitfalls, and this part of the author will solve the possible pitfalls for readers and friends!

3.1 Raspberry Pi 4B code 

We use Python code to write a code program that sends numbers in a loop. The specific code is as follows:

import serial  
import time  
  
ser = serial.Serial('/dev/ttyAMA0',115200) # 串口初始化,根据实际情况修改串口号和波特率  

# 定义要输出的数字  
num =  196 

while True:  
                
    ser.write(str(int(num)).encode()) # 发送数字到串口   
    num += 1  
    if num > 205:  
        num = 196
     
    time.sleep(0.2) # 等待1秒钟  

It can be seen that the code is very simple, but readers here need to pay attention to that the port of Raspberry Pi 4B sends to STM32 is actually a string stream ! On the STM32 side, we decode the sent string stream (many bloggers actually did not explain this point, which caused many friends to fail to decode)!

3.2 CubeMX configuration

1. RCC is configured with an external high-speed crystal oscillator (higher precision) - HSE;

2. SYS configuration: Debug is set to Serial Wire ( otherwise it may cause the chip to self-lock );

3. I2C configuration:

4. USART1 configuration: set UART1 serial port; baud rate: 115200; enable UART serial port interrupt;

5. Clock tree configuration

6. Engineering configuration

3.3 STM32 code

3.3.1 OLED Code

The OLED module is mainly to facilitate the display of data information sent by Raspberry Pi 4B to STM32! Considering the actual situation, we generally need to use the digital information sent by Raspberry Pi 4B, so here we use OLED for digital display!

Decimal display API function:

//z_len为整数显示位数,f_len为小数显示位数,size2为字体大小
void OLED_Showdecimal(u8 x,u8 y,float num,u8 z_len,u8 f_len,u8 size2)
{         	
	u8 t,temp;
	u8 enshow;
	int z_temp,f_temp;      
	z_temp=(int)num;
	//整数部分
	for(t=0;t<z_len;t++)
	{
		temp=(z_temp/oled_pow(10,z_len-t-1))%10;
		if(enshow==0 && t<(z_len-1))
		{
			if(temp==0)
			{
				OLED_ShowChar(x+(size2/2)*t,y,' ',size2);
				continue;
			}
			else
			enshow=1;
		}
		OLED_ShowChar(x+(size2/2)*t,y,temp+'0',size2); 
	}
	//小数点
	OLED_ShowChar(x+(size2/2)*(z_len),y,'.',size2); 
	
	f_temp=(int)((num-z_temp)*(oled_pow(10,f_len)));
  //小数部分
	for(t=0;t<f_len;t++)
	{
		temp=(f_temp/oled_pow(10,f_len-t-1))%10;
		OLED_ShowChar(x+(size2/2)*(t+z_len)+5,y,temp+'0',size2); 
	}
}

Space is limited, OLED reference blog: http://t.csdn.cn/kydg4

3.3.2 UART code

This part of the code is relatively core. The above-mentioned blogger has already explained that the data sent by the Raspberry Pi 4B to the STM32 is sent in the format of a string stream. Therefore, even if the digital data is sent, it will become characters, which requires us to decode it!

uart.h:

#ifndef __UART_H
#define __UART_H

#include "stm32f1xx_hal.h" 

extern UART_HandleTypeDef huart1;

#define USART1_REC_LEN  600

extern int  USART1_RX_BUF[USART1_REC_LEN];
extern uint16_t USART1_RX_STA;
extern int USART1_NewData;

void  HAL_UART_RxCpltCallback(UART_HandleTypeDef  *huart);

#endif

uart.c:

#include "uart.h"
#include "oled.h"

int USART1_RX_BUF[USART1_REC_LEN];		//目标数据
uint16_t USART1_RX_STA=2;
int USART1_NewData;

extern int num;		//百位
extern int num2;    //十位
extern int num3;    //个位


void  HAL_UART_RxCpltCallback(UART_HandleTypeDef  *huart)
{
    if(huart ==&huart1)
    { 
			
      USART1_RX_BUF[USART1_RX_STA&0X7FFF]=USART1_NewData; 					
      USART1_RX_STA++;  
			
						
      if(USART1_RX_STA>(USART1_REC_LEN-1))USART1_RX_STA=0;

			//num = USART1_RX_BUF[USART1_RX_STA];
			
			HAL_UART_Receive_IT(&huart1,(uint8_t *)&USART1_NewData,1);
			
			num = USART1_RX_BUF[USART1_RX_STA-1];			
			num2 = USART1_RX_BUF[USART1_RX_STA-2];
			num3 = USART1_RX_BUF[USART1_RX_STA-3];			
    }		
}

The above UART code uses the UART interrupt function to read the value of USART1_NewData , because the maximum number we can transmit is 3 digits, so we read the latest 3 bytes of data in the buffer array (the data sent by Raspberry Pi 4B is A string, that is, an ASCII value converted into a corresponding number, for example: if 100 is sent, the STM32 end will receive 3 bytes of 49 49 48 ).

3.3.3 Data decoding code

control.c:

#include "control.h"
#include "uart.h"
#include "tim.h"
#include "oled.h"

int num;
int num2;
int num3;
int value;
int flag;
int last;


void TargetTracking()
{
	flag = USART1_RX_STA - last;
				
	last = USART1_RX_STA;
	
	value = (num3-48) * 100 + (num2-48) * 10 + (num-48) * 1;
	
	OLED_ShowStr(10,2,"Object Center",2);
	OLED_Showdecimal(45,4,value,3,1,16);
	
	if(flag == 2)
	{
		value = (num2-48) * 10 + (num-48) * 1;
		OLED_Showdecimal(40,4,value,3,1,16);
	}
	
}

The default here is 3 digits, so according to the high and low data of UART data transmission, the data -48 will be changed into the actual number, and the actual value can be obtained in the ratio corresponding to ×! The flag is  to judge the number of bytes of data transmitted at a time through the change value of the USART1_RX_STA variable, and it can be judged how many digits it is!

Readers and friends can change the above code according to their actual situation for their own use!

After the code runs:

4. Advanced application

Target Tracking for Smart Cars

The Raspberry Pi 4B usually appears in the tracking of specified targets based on vision technology. At this time, the Raspberry Pi 4B often needs to read the target frame data, and then send it to the STM32 lower computer. After that, the STM32 performs logic based on the target frame information. control.

The author here takes the network model detection results of the previous blog as an example, the code is as follows:

import cv2
import numpy as np
import onnxruntime as ort
import serial
import time

ser = serial.Serial('/dev/ttyAMA0',115200)

def plot_one_box(x, img, color=None, label=None, line_thickness=None):
    """
    description: Plots one bounding box on image img,
                 this function comes from YoLov5 project.
    param: 
        x:      a box likes [x1,y1,x2,y2]
        img:    a opencv image object
        color:  color to draw rectangle, such as (0,255,0)
        label:  str
        line_thickness: int
    return:
        no return
    """
    tl = (
        line_thickness or round(0.002 * (img.shape[0] + img.shape[1]) / 2) + 1
    )  # line/font thickness
    color = color or [random.randint(0, 255) for _ in range(3)]
    c1, c2 = (int(x[0]), int(x[1])), (int(x[2]), int(x[3]))
        
    ser.write(str(int((int(x[2])-int(x[0]))/2+int(x[0]))).encode())
    print(int((int(x[2])-int(x[0]))/2+int(x[0])))
        
    cv2.rectangle(img, c1, c2, color, thickness=tl, lineType=cv2.LINE_AA)
    if label:
        tf = max(tl - 1, 1)  # font thickness
        t_size = cv2.getTextSize(label, 0, fontScale=tl / 3, thickness=tf)[0]
        c2 = c1[0] + t_size[0], c1[1] - t_size[1] - 3
        cv2.rectangle(img, c1, c2, color, -1, cv2.LINE_AA)  # filled
        cv2.putText(
            img,
            label,
            (c1[0], c1[1] - 2),
            0,
            tl / 3,
            [225, 255, 255],
            thickness=tf,
            lineType=cv2.LINE_AA,
        )

def _make_grid( nx, ny):
        xv, yv = np.meshgrid(np.arange(ny), np.arange(nx))
        return np.stack((xv, yv), 2).reshape((-1, 2)).astype(np.float32)

def cal_outputs(outs,nl,na,model_w,model_h,anchor_grid,stride):
    
    row_ind = 0
    grid = [np.zeros(1)] * nl
    for i in range(nl):
        h, w = int(model_w/ stride[i]), int(model_h / stride[i])
        length = int(na * h * w)
        if grid[i].shape[2:4] != (h, w):
            grid[i] = _make_grid(w, h)

        outs[row_ind:row_ind + length, 0:2] = (outs[row_ind:row_ind + length, 0:2] * 2. - 0.5 + np.tile(
            grid[i], (na, 1))) * int(stride[i])
        outs[row_ind:row_ind + length, 2:4] = (outs[row_ind:row_ind + length, 2:4] * 2) ** 2 * np.repeat(
            anchor_grid[i], h * w, axis=0)
        row_ind += length
    return outs



def post_process_opencv(outputs,model_h,model_w,img_h,img_w,thred_nms,thred_cond):
    conf = outputs[:,4].tolist()
    c_x = outputs[:,0]/model_w*img_w
    c_y = outputs[:,1]/model_h*img_h
    w  = outputs[:,2]/model_w*img_w
    h  = outputs[:,3]/model_h*img_h
    p_cls = outputs[:,5:]
    if len(p_cls.shape)==1:
        p_cls = np.expand_dims(p_cls,1)
    cls_id = np.argmax(p_cls,axis=1)

    p_x1 = np.expand_dims(c_x-w/2,-1)
    p_y1 = np.expand_dims(c_y-h/2,-1)
    p_x2 = np.expand_dims(c_x+w/2,-1)
    p_y2 = np.expand_dims(c_y+h/2,-1)
    areas = np.concatenate((p_x1,p_y1,p_x2,p_y2),axis=-1)
    
    areas = areas.tolist()
    ids = cv2.dnn.NMSBoxes(areas,conf,thred_cond,thred_nms)
    if len(ids)>0:
        return  np.array(areas)[ids],np.array(conf)[ids],cls_id[ids]
    else:
        return [],[],[]
def infer_img(img0,net,model_h,model_w,nl,na,stride,anchor_grid,thred_nms=0.4,thred_cond=0.5):
    # 图像预处理
    img = cv2.resize(img0, [model_w,model_h], interpolation=cv2.INTER_AREA)
    img = cv2.cvtColor(img, cv2.COLOR_BGR2RGB)
    img = img.astype(np.float32) / 255.0
    blob = np.expand_dims(np.transpose(img, (2, 0, 1)), axis=0)

    # 模型推理
    outs = net.run(None, {net.get_inputs()[0].name: blob})[0].squeeze(axis=0)

    # 输出坐标矫正
    outs = cal_outputs(outs,nl,na,model_w,model_h,anchor_grid,stride)

    # 检测框计算
    img_h,img_w,_ = np.shape(img0)
    boxes,confs,ids = post_process_opencv(outs,model_h,model_w,img_h,img_w,thred_nms,thred_cond)

    return  boxes,confs,ids




if __name__ == "__main__":

    # 模型加载
    model_pb_path = "best.onnx"
    so = ort.SessionOptions()
    net = ort.InferenceSession(model_pb_path, so)
    
    # 标签字典
    dic_labels= {0:'drug',
            1:'glue',
            2:'prime'}
    
    # 模型参数
    model_h = 320
    model_w = 320
    nl = 3
    na = 3
    stride=[8.,16.,32.]
    anchors = [[10, 13, 16, 30, 33, 23], [30, 61, 62, 45, 59, 119], [116, 90, 156, 198, 373, 326]]
    anchor_grid = np.asarray(anchors, dtype=np.float32).reshape(nl, -1, 2)
    
    video = 0
    cap = cv2.VideoCapture(video)
    flag_det = False
    while True:
        success, img0 = cap.read()
        if success:
            
            if flag_det:
                t1 = time.time()
                det_boxes,scores,ids = infer_img(img0,net,model_h,model_w,nl,na,stride,anchor_grid,thred_nms=0.4,thred_cond=0.5)
                t2 = time.time()
            
                
                for box,score,id in zip(det_boxes,scores,ids):
                    label = '%s:%.2f'%(dic_labels[id],score)
            
                    plot_one_box(box.astype(np.int16), img0, color=(255,0,0), label=label, line_thickness=None)
                    
                str_FPS = "FPS: %.2f"%(1./(t2-t1))
                
                cv2.putText(img0,str_FPS,(50,50),cv2.FONT_HERSHEY_COMPLEX,1,(0,255,0),3)
                
            
            cv2.imshow("video",img0)
        key=cv2.waitKey(1) & 0xFF    
        if key == ord('q'):
        
            break
        elif key & 0xFF == ord('s'):
            flag_det = not flag_det
            print(flag_det)
            
    cap.release() 
    
    

The author’s above code only takes the x-axis coordinates of the center of the target object as an example. The control mechanism is as follows: when the x value is greater than 320 (the picture is 640×640), the control car moves to the right, otherwise it moves to the left. The w and h of the target frame can set the threshold according to the actual situation to control the forward speed of the car. When the width w of the target frame is too small, accelerate the car to move forward, otherwise slow down!

The author has something to say:

The FPS of the current YOLOv-Lite network model is still too low, and it is very difficult to control target tracking at this FPS . In addition, in reality, the camera mounted on the car or the aircraft cannot avoid strong Gaussian white noise during the shooting process, and Kalman filtering is needed to optimize the target frame information!

Therefore, the follow-up author will launch a network model and target tracking code that can be based on actual visual tracking. Interested readers and friends can look forward to it!

5. Project effect

Communication tracking based on Raspberry Pi 4B and STM32

6. Project Code

Code address: UART serial communication experiment code resources based on Raspberry Pi 4B and STM32-CSDN library

If you don't have enough points, click Bo to follow , leave an email in the comment area , and the author will provide the source code and follow-up questions for free . Please pay attention to a wave! ! !

Guess you like

Origin blog.csdn.net/black_sneak/article/details/131484958