基于Jetson Nano与STM32通信的颜色识别与伺服驱动器控制
本文主要是使用Jetson Nano通过颜色识别识别物体后,将目标中心点坐标与摄像头中心点坐标的误差传送到stm32开发板。由stm32判断数据进行一系列操作,并使用定时器产生PWM驱动伺服驱动器使摄像头中心正对目标中心。
jetrson nano部分
jetson nano主要负责图像的识别和误差坐标(x轴和y轴)的传输,我这里为了实验方便使用的是opencv的HSV色域颜色识别,也可以使用神经网络。 其中需要的库包括
import cv2
import numpy as np
import serial
import struct,time
import sys
有些可能没用到
颜色识别
cam= cv2.VideoCapture(0)
l_b=np.array([0,130,105])
u_b=np.array([4,255,217])
l_b2=np.array([166,130,105])
u_b2=np.array([179,255,217])
ret, frame = cam.read()
frame = cv2.resize(frame, (width, height))
frame_=cv2.GaussianBlur(frame,(5,5),0)
hsv=cv2.cvtColor(frame,cv2.COLOR_BGR2HSV)
FGmask=cv2.inRange(hsv,l_b,u_b)
FGmask2=cv2.inRange(hsv,l_b2,u_b2)
mask=cv2.add(FGmask,FGmask2)
mask=cv2.erode(mask,None,iterations=2)
mask=cv2.dilate(mask,None,iterations=2)
mask=cv2.GaussianBlur(mask,(3,3),0)
cnts=cv2.findContours(mask.copy(),cv2.RETR_EXTERNAL,cv2.CHAIN_APPROX_SIMPLE)[-2]
if len(cnts)>0:
cnt = max (cnts,key=cv2.contourArea)
(color_x,color_y),color_radius=cv2.minEnclosingCircle(cnt)
if color_radius > 10:
cv2.circle(frame,(int(color_x),int(color_y)),int(color_radius),(255,0,255),2)
串口通信
串口通信函数,主要参考:基于JETSON NANO的激光测距和色块识别综合代码(包括和STM32通信)连接的是stm32UART1 注意!!!使用前需要开启 ttyTHS1 打开串口权限(jetson 系列好像每次开机都需要这样做),在终端使用sudo chmod 777 ‘/dev/tthTHS1’ .如果想开机自启动打开权限请参考:linux systemctl命令添加开机启动脚本
class Comcontrol(serial.Serial):
def __init__(self, port, baudrate, bytesize, stopbits, timeout, parity):
super(Comcontrol, self).__init__()
self.port = port
self.baudrate = baudrate
self.bytesize = bytesize
self.stopbits = stopbits
self.timeout = timeout
self.parity = parity
self.com = serial.Serial(port = self.port,
baudrate = self.baudrate,
bytesize = self.bytesize,
stopbits = self.stopbits,
timeout = self.timeout,
parity = self.parity)
def mpu_com_connect():
mpucom = Comcontrol(port = '/dev/ttyTHS1',
baudrate = 115200,
bytesize = 8,
stopbits = 1,
timeout = 0.8,
parity = 'N')
if(mpucom.com.is_open):
print("mpu connection success\r\n")
return mpucom
数据传输
x_bias = int(color_x - width/2)
y_bias = int(color_y - height/2)
mpucom.com.write('#'.encode()+str(int(x_bias)).encode()+'e'.encode())
mpucom.com.write('$'.encode()+str(int(y_bias)).encode()+'e'.encode())
print('Y'.encode()+str(int(y_bias)).encode()+'e'.encode())
print('X'.encode()+str(int(x_bias)).encode()+'e'.encode())
添加报头报尾,方便判断x轴y轴,也方便判断数据位数。 事先确定好数据长度,我这样正好,最多也不会超过8位。 串口只能发送为str()格式的数据,同时,如果有汉字可以使用‘汉字’.encode('utf-8')
完整代码
import cv2
import numpy as np
import serial
import struct,time
import sys
print(cv2.__version__)
def nothing(x):
pass
class Comcontrol(serial.Serial):
def __init__(self, port, baudrate, bytesize, stopbits, timeout, parity):
super(Comcontrol, self).__init__()
self.port = port
self.baudrate = baudrate
self.bytesize = bytesize
self.stopbits = stopbits
self.timeout = timeout
self.parity = parity
self.com = serial.Serial(port = self.port,
baudrate = self.baudrate,
bytesize = self.bytesize,
stopbits = self.stopbits,
timeout = self.timeout,
parity = self.parity)
def mpu_com_connect():
mpucom = Comcontrol(port = '/dev/ttyTHS1',
baudrate = 115200,
bytesize = 8,
stopbits = 1,
timeout = 0.8,
parity = 'N')
if(mpucom.com.is_open):
print("mpu connection success\r\n")
return mpucom
cam= cv2.VideoCapture(0)
width = 400
height = 400
l_b=np.array([0,130,105])
u_b=np.array([4,255,217])
l_b2=np.array([166,130,105])
u_b2=np.array([179,255,217])
mpucom = mpu_com_connect()
while 1:
ret, frame = cam.read()
frame = cv2.resize(frame, (width, height))
frame_=cv2.GaussianBlur(frame,(5,5),0)
hsv=cv2.cvtColor(frame,cv2.COLOR_BGR2HSV)
FGmask=cv2.inRange(hsv,l_b,u_b)
FGmask2=cv2.inRange(hsv,l_b2,u_b2)
mask=cv2.add(FGmask,FGmask2)
mask=cv2.erode(mask,None,iterations=2)
mask=cv2.dilate(mask,None,iterations=2)
mask=cv2.GaussianBlur(mask,(3,3),0)
cnts=cv2.findContours(mask.copy(),cv2.RETR_EXTERNAL,cv2.CHAIN_APPROX_SIMPLE)[-2]
if len(cnts)>0:
cnt = max (cnts,key=cv2.contourArea)
(color_x,color_y),color_radius=cv2.minEnclosingCircle(cnt)
if color_radius > 10:
cv2.circle(frame,(int(color_x),int(color_y)),int(color_radius),(255,0,255),2)
x_bias = int(color_x - width/2)
y_bias = int(color_y - height/2)
mpucom.com.write('#'.encode()+str(int(x_bias)).encode()+'e'.encode())
mpucom.com.write('$'.encode()+str(int(y_bias)).encode()+'e'.encode())
print('Y'.encode()+str(int(y_bias)).encode()+'e'.encode())
print('X'.encode()+str(int(x_bias)).encode()+'e'.encode())
else:
print('N')
mpucom.com.write('N'.encode())
if cv2.waitKey(1) == ord('q'):
break
cam.release()
cv2.destroyAllWindows()
stm32 部分
stm32部分主要分为数据解读和伺服驱动器控制部分,使用到的常规led beep代码就不放了,可以自行设计。 stm32不仅要产生PWM波控制伺服驱动器,更要考虑实际情况进行软件限位,即精确获得产出的PWM数。 这里使用的伺服驱动器是台达的A2,使用差分信号驱动模式,实测stm32的3.3V电压可以驱动。
数据解读
stm32f10x_it.c
static u8 i=0;
static u8 j=0;
char uctemp[8] = {0};
char x_temp[8] = {0};
char y_temp[8] = {0};
extern volatile int x_bais;
extern volatile int y_bais;
extern volatile int target;
extern volatile int receive;
extern volatile int Rotation_angle;
extern volatile int Limit_angle;
首先判断是否存在目标,如果不存在则不启动电机,同时亮红灯表示; 检测到目标则亮绿灯,同时可以启动电机,并判断出x轴y轴偏移误差,将char转化为int。
atoi(‘124e’)= 124;最后的‘e’会被忽略掉。
void DEBUG_USART_IRQHandler(void)
{
u8 k=0;
if(USART_GetITStatus(DEBUG_USARTx,USART_IT_RXNE)!=RESET)
{
receive = 3;
uctemp[i] = USART_ReceiveData(DEBUG_USARTx);
j=i;
if((uctemp[0] != '#'&&uctemp[0] != '$')||uctemp[i]=='e') i=0;
if(uctemp[0] == 'N')
{
target=0;
LED2_OFF;
LED1_ON;
x_bais = 0;
y_bais = 0;
}
else if((uctemp[0] == '#') &&(uctemp[j] == 'e'))
{
target=1;
LED1_OFF;
LED2_ON;
for(k=0;k<j;k++){
x_temp[k] = uctemp[k+1];
}
x_bais = atoi(x_temp);
}
else if((uctemp[0] == '$') &&(uctemp[j] == 'e'))
{
target=1;
LED1_OFF;
LED2_ON;
for(k=0;k<j;k++){
y_temp[k] = uctemp[k+1];
}
y_bais = atoi(y_temp);
}else{i++;}
}
}
电机控制
驱动伺服电机需要使用pwm波,我采用通用定时器产生PWM波,同时为了精确限位,使用另一个从定时器统计产生的脉冲数量。 因为伺服驱动器是通过脉冲数量来驱动电机运行的,本文设置的3600脉冲转一转,则转一度需要10脉冲
timer.c
#include "stm32f10x.h"
#include "timer.h"
void Master_TIM(u16 period,u16 prescaler,u16 pulse)
{
GPIO_InitTypeDef GPIO_InitStructure;
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_7;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(GPIOA, &GPIO_InitStructure);
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3,ENABLE);
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
TIM_TimeBaseStructure.TIM_Period=period;
TIM_TimeBaseStructure.TIM_Prescaler= prescaler;
TIM_TimeBaseStructure.TIM_ClockDivision=TIM_CKD_DIV1;
TIM_TimeBaseStructure.TIM_CounterMode=TIM_CounterMode_Up;
TIM_TimeBaseStructure.TIM_RepetitionCounter=0;
TIM_TimeBaseInit(TIM3, &TIM_TimeBaseStructure);
TIM_OCInitTypeDef TIM_OCInitStructure;
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High;
TIM_OCInitStructure.TIM_Pulse = pulse;
TIM_OC2Init(TIM3, &TIM_OCInitStructure);
TIM_OC2PreloadConfig(TIM3, TIM_OCPreload_Enable);
TIM_Cmd(TIM3, DISABLE);
TIM_SelectMasterSlaveMode(TIM3,TIM_MasterSlaveMode_Enable);
TIM_SelectOutputTrigger(TIM3,TIM_TRGOSource_Update);
}
void Slave_TIM(u16 period)
{
NVIC_InitTypeDef NVIC_InitStructure;
TIM_TimeBaseInitTypeDef TIM_TimeBaseInitStructure;
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM4,ENABLE);
TIM_TimeBaseInitStructure.TIM_ClockDivision=TIM_CKD_DIV1;
TIM_TimeBaseInitStructure.TIM_CounterMode=TIM_CounterMode_Up;
TIM_TimeBaseInitStructure.TIM_Period=period;
TIM_TimeBaseInitStructure.TIM_Prescaler=0;
TIM_TimeBaseInitStructure.TIM_RepetitionCounter=0;
TIM_TimeBaseInit(TIM4,&TIM_TimeBaseInitStructure);
TIM_SelectSlaveMode(TIM4,TIM_SlaveMode_External1);
TIM_SelectInputTrigger(TIM4,TIM_TS_ITR2);
TIM_Cmd(TIM4,DISABLE);
NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);
NVIC_InitStructure.NVIC_IRQChannel=TIM4_IRQn;
NVIC_InitStructure.NVIC_IRQChannelCmd=ENABLE;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority=2;
NVIC_InitStructure.NVIC_IRQChannelSubPriority=2;
NVIC_Init(&NVIC_InitStructure);
TIM_ITConfig(TIM4,TIM_IT_Update,ENABLE);
}
void DIR_Crl(void)
{
GPIO_InitTypeDef GPIO_InitStructure;
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOE,ENABLE);
GPIO_InitStructure.GPIO_Mode=GPIO_Mode_Out_PP;
GPIO_InitStructure.GPIO_Pin=GPIO_Pin_9;
GPIO_InitStructure.GPIO_Speed=GPIO_Speed_50MHz;
GPIO_Init(GPIOE,&GPIO_InitStructure);
}
主函数
主函数主要是控制电机,因为x轴y轴的控制方式基本一样,我这里只写了一个电机的控制,需要两个的可以复制粘贴,稍微修改就可以了。
#include "stm32f10x.h"
#include "bsp_usart.h"
#include <stdlib.h>
#include <stdio.h>
#include "bsp_led.h"
#include "systick.h"
#include "bsp_beep.h"
#include "timer.h"
volatile int x_bais;
volatile int y_bais;
volatile int target;
volatile int receive = 3;
volatile int Rotation_angle = 100;
volatile int Limit_angle = 90;
int main(void)
{
int Pulse_num = Rotation_angle*10;
int value_num = 100000/Pulse_num - 1;
int Duty_cycle = 50;
int cycle_num = (Duty_cycle*value_num)/100;
USART_Config();
initSysTick();
LED_GPIO_Config();
BEEP_GPIO_Config();
Usart_SendString( DEBUG_USARTx,"串口通讯调试实验\n");
Master_TIM(value_num,719,cycle_num);
DIR_Crl();
Motor_CW;
Slave_TIM(20);
delay_ms(10);
TIM_Cmd(TIM4,ENABLE);
while(1)
{
if(receive == 0)
{
TIM_Cmd(TIM3,DISABLE);
BEEP(1);
delay_ms(1000);
printf("长时间未接收到数据,系统异常!!!\n");
}
else{
BEEP(0);
receive--;
if(target == 1)
{
if(x_bais > 5 && Limit_angle <= 150)
{
Motor_CW;
TIM_Cmd(TIM3,ENABLE);
}
else if(x_bais < -5 && Limit_angle >= 50)
{
Motor_CCW;
TIM_Cmd(TIM3,ENABLE);
}else TIM_Cmd(TIM3,DISABLE);
}else TIM_Cmd(TIM3,DISABLE);
}
}
}
电机加减速
我目前的实验没有用到加减速,但是可以作为全局变量放进去自动控制。 暂时使用的是外部中断
#include "bsp_exti.h"
static void EXTI_NVIC_Config(void)
{
NVIC_InitTypeDef NVIC_InitStructure1;
NVIC_InitTypeDef NVIC_InitStructure2;
NVIC_PriorityGroupConfig(NVIC_PriorityGroup_1);
NVIC_InitStructure1.NVIC_IRQChannel = EXTI0_IRQn;
NVIC_InitStructure1.NVIC_IRQChannelPreemptionPriority = 1;
NVIC_InitStructure1.NVIC_IRQChannelSubPriority = 1;
NVIC_InitStructure1.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init( &NVIC_InitStructure1);
NVIC_PriorityGroupConfig(NVIC_PriorityGroup_1);
NVIC_InitStructure2.NVIC_IRQChannel = EXTI15_10_IRQn;
NVIC_InitStructure2.NVIC_IRQChannelPreemptionPriority = 1;
NVIC_InitStructure2.NVIC_IRQChannelSubPriority = 1;
NVIC_InitStructure2.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init( &NVIC_InitStructure2);
}
void EXTI_KEY_Config(void)
{
GPIO_InitTypeDef GPIO_InitStructure;
EXTI_InitTypeDef EXTI_InitStructure1;
EXTI_InitTypeDef EXTI_InitStructure2;
EXTI_NVIC_Config();
RCC_APB2PeriphClockCmd(KEY1_GPIO_CLK|KEY2_GPIO_CLK|RCC_APB2Periph_AFIO,ENABLE);
GPIO_InitStructure.GPIO_Pin = KEY1_GPIO_PIN;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
GPIO_Init(KEY1_GPIO_PORT, &GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = KEY2_GPIO_PIN;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
GPIO_Init(KEY2_GPIO_PORT, &GPIO_InitStructure);
GPIO_EXTILineConfig(GPIO_PortSourceGPIOA, GPIO_PinSource0);
EXTI_InitStructure1.EXTI_Line = EXTI_Line0;
EXTI_InitStructure1.EXTI_Mode = EXTI_Mode_Interrupt;
EXTI_InitStructure1.EXTI_Trigger = EXTI_Trigger_Rising;
EXTI_InitStructure1.EXTI_LineCmd = ENABLE;
EXTI_Init( &EXTI_InitStructure1);
GPIO_EXTILineConfig(GPIO_PortSourceGPIOC, GPIO_PinSource13);
EXTI_InitStructure2.EXTI_Line = EXTI_Line13;
EXTI_InitStructure2.EXTI_Mode = EXTI_Mode_Interrupt;
EXTI_InitStructure2.EXTI_Trigger = EXTI_Trigger_Rising;
EXTI_InitStructure2.EXTI_LineCmd = ENABLE;
EXTI_Init( &EXTI_InitStructure2);
}
void EXTI0_IRQHandler(void)
{
if(EXTI_GetITStatus( EXTI_Line0)!= RESET)
{
Rotation_angle+=10;
printf("Rotation_angle = %d\r\n",Rotation_angle);
}
EXTI_ClearITPendingBit(EXTI_Line0);
}
void EXTI15_10_IRQHandler(void)
{
if(EXTI_GetITStatus( EXTI_Line13)!= RESET)
{
Rotation_angle-=10;
printf("Rotation_angle = %d\r\n",Rotation_angle);
}
EXTI_ClearITPendingBit(EXTI_Line13);
}
硬件图:
STM32 : 伺服驱动器 41号,37号接stm32的GND 43号连接PA7(TIM3的channel2 PWM输出通道) 36号连接PE9(转动方向控制)
Stm32的PA9链接串口RX(用于发送到上位机观看数据)
切记,伺服驱动器的接地工作一定要做好,不然会出现即使不上电或者不给信号电机依旧会转的情况。
jetson nano: 硬件连线如图,8号(TX)接PA10(UART1_RX),10号(RX)可以用来接收stm32的信息,PA9(UART1_TX)
总结
以上就是整个程序了,除了一些小细节外其他的应该都比较清楚,欢迎有想法或者有疑问的同学提问,如果有错误也欢迎指正!
|