ros和stm32等嵌入式单片机的最大区别在于ros主要用于处理slam、机器视觉、人工智能这种对于算力要求高,算法复杂的问题;而stm32和arduino等主要用来处理一些边缘事件,比如亮个LED,驱动个电机啥的。相比于ros,实时性强是嵌入式单片机最大的优点(以我做的两轮平衡小车为例,stm32f103的一个周期大概为3ms左右),所以ros和单片机的通讯是必然的。
这篇文章是基于ros的串口函数库来和stm32进行串口通讯。stm32采用usart+dma接收数据。同时也可移植arduino等平台。
1.安装串口库
$ sudo apt-get install ros-<版本号>-serial
2.创建talker功能包,基于rospy、roscpp、serial这三个包
catkin_create_pkg stm32_talker rospy roscpp serial
3.在此功能包下创建两个消息stm32_message_bag和stm32_message_back,分别是发送给stm32的命令和stm32回传的消息,并且将其包含在CMakeList中
消息内容为:
//stm32_message_back
uint8 data0
uint8 data1
uint8 data2
uint8 data3
uint8 data4
uint8 data5
uint8 data6
uint8 data7
//stm32_message_back
uint8 data0
uint8 data1
uint8 data2
uint8 data3
uint8 data4
uint8 data5
uint8 data6
uint8 data7
消息内容是一样的,创建两个只是为了区分,不差这点内存。
4.在src下新建stm32_talker.cpp,并且输入以下代码:
#include
#include
#include
stm32_talker::stm32_message_bag msg;//声明命令变量
/****初始化命令****/
void init_message_command()
{
msg.data0=0x01;
msg.data1=0x01;
msg.data2=0x01;
msg.data3=0x01;
msg.data4=0x01;
msg.data5=0x01;
msg.data6=0x01;
msg.data7=0x01;
}
/****接收到stm32反馈后的回调函数****/
void stm32backcallback(const stm32_talker::stm32_message_bag::ConstPtr& back)
{
ROS_INFO("I heard back");
uint8_t stm32_back[10];
size_t n=8;
stm32_back[0]=back->data0;
stm32_back[1]=back->data1;
stm32_back[2]=back->data2;
stm32_back[3]=back->data3;
stm32_back[4]=back->data4;
stm32_back[5]=back->data5;
stm32_back[6]=back->data6;
stm32_back[7]=back->data7;
for(int i=0;i<=7;i++)
{
ROS_INFO("%02x",stm32_back[i]);
}
}
int main(int argc, char **argv)
{
ros::init(argc,argv,"stm32_talker");
ros::NodeHandle n;
ros::Rate loop_rate(10);
ros::Publisher stm32_command_pub = n.advertise<stm32_talker::stm32_message_bag>("stm32_command",1000);//发布命令
ros::Subscriber stm32_back_sub = n.subscribe("stm32_back",1000,stm32backcallback);//订阅反馈
while(ros::ok())
{
init_message_command();
stm32_command_pub.publish(msg);//发布命令
loop_rate.sleep();
ros::spinOnce();
}
}
5.创建listener功能包,基于rospy、roscpp、serial、stm32_talker这四个包
catkin_create_pkg stm32_listener rospy roscpp serial stm32_talker
6.在listener功能包下,src文件夹中新建stm32_listener.cpp,并且输入以下代码:
#include
#include
#include
#include
serial::Serial ser;//串口变量
//打开串口
void openserial()
{
try
{
ser.setPort("/dev/ttyUSB0");//设备端口号
ser.setBaudrate(38400);//波特率
serial::Timeout t = serial::Timeout::simpleTimeout(1000);//这个应该是超时,但是是必须的!!
ser.setTimeout(t);
ser.open();//打开串口
}
catch (serial::IOException& e)
{
ROS_ERROR_STREAM("Unable to open port ");
}
if(ser.isOpen())
{
ROS_INFO("OPEN");
}
}
//订阅到talker后的回调函数
void stm32commandcallback(const stm32_talker::stm32_message_bag::ConstPtr& command)
{
ROS_INFO("I heard talker");
uint8_t data[10];
size_t n=8;
data[0]=command->data0;
data[1]=command->data1;
data[2]=command->data2;
data[3]=command->data3;
data[4]=command->data4;
data[5]=command->data5;
data[6]=command->data6;
data[7]=command->data7;
ser.write(data,n);
}
int main(int argc,char **argv)
{
ros::init(argc,argv,"stm32_listener");
ros::NodeHandle m;
openserial(); //打开串口
ros::Subscriber stm32_command_sub = m.subscribe("stm32_command",1000,stm32commandcallback);
ros::Publisher stm32_back_pub = m.advertise<stm32_talker::stm32_message_back>("stm32_back",1000);
while(ros::ok())
{
size_t w=ser.available();//串口缓存区字节数
uint8_t buffer[10];
if(w!=0)
{
ser.read(buffer,w);
stm32_talker::stm32_message_back msg_back;
msg_back.data0=buffer[0];
msg_back.data1=buffer[1];
msg_back.data2=buffer[2];
msg_back.data3=buffer[3];
msg_back.data4=buffer[4];
msg_back.data5=buffer[5];
msg_back.data6=buffer[6];
msg_back.data7=buffer[7];
w=0;
stm32_back_pub.publish(msg_back);
ROS_INFO("BACK");
}
ros::spinOnce();
}
}
工程文件的创建不再赘述,主函数代码如下:
#include"stm32f10x.h"
#include"systick.h"
//PA9_TX PA10_RX
uint8_t USART1_RX_BUF[8];
uint8_t USART1_TX_BUF[8];
int sig=0;
void SBUS_Configuration(void);
void DMA_Config(void);
void Data_Back_Init(void);
void Send_Data();
int main()
{
SBUS_Configuration();
DMA_Config();
while(1)
{
Data_Back_Init();
Send_Data();
delay_ms(500);
}
}
void Data_Back_Init(void)
{
USART1_TX_BUF[0]=0x00;
USART1_TX_BUF[1]=0x00;
USART1_TX_BUF[2]=0x00;
USART1_TX_BUF[3]=0x00;
USART1_TX_BUF[4]=0x00;
USART1_TX_BUF[5]=0x00;
USART1_TX_BUF[6]=0x00;
USART1_TX_BUF[7]=0x00;
}
void Send_Data()
{
for(int i=0;i<=7;i++)
{
USART_SendData(USART1,USART1_TX_BUF[i]);
}
}
void SBUS_Configuration(void)
{
GPIO_InitTypeDef GPIO_InitStructure;
USART_InitTypeDef USART_InitStructure;
NVIC_InitTypeDef NVIC_InitStructure;
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA| RCC_APB2Periph_AFIO, ENABLE);
RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1,ENABLE);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
GPIO_Init(GPIOA, &GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_9;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP; //复用推挽输出
GPIO_Init(GPIOA, &GPIO_InitStructure); //初始化PA.9
// 波特率100000 8个数据位 无校验位 1个停止位
USART_InitStructure.USART_BaudRate = 38400;
USART_InitStructure.USART_WordLength = USART_WordLength_8b;
USART_InitStructure.USART_StopBits = USART_StopBits_1;
USART_InitStructure.USART_Parity = USART_Parity_NO;
USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
USART_DMACmd(USART1,USART_DMAReq_Rx,ENABLE);
USART_Init(USART1, &USART_InitStructure);
USART_ITConfig(USART1, USART_IT_RXNE, DISABLE);
USART_ITConfig(USART1, USART_IT_IDLE, ENABLE);//采取串口空闲中断来处理数据
USART_Cmd(USART1, ENABLE);
NVIC_InitStructure.NVIC_IRQChannel = USART1_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
}
void DMA_Config()
{
DMA_InitTypeDef DMA_InitStructure;
DMA_DeInit(DMA1_Channel5);
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE); // 开启DMA时钟
DMA_InitStructure.DMA_PeripheralBaseAddr = 0x40013804; // 设置DMA源地址:串口数据寄存器地址*/
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)USART1_RX_BUF; // 内存地址(要传输的变量的指针)
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC; // 方向:外设到内存
DMA_InitStructure.DMA_BufferSize = 8; // 传输大小
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable; // 外设地址不增
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable; // 内存地址自增
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte; // 外设数据单位
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte; // 内存数据单位
DMA_InitStructure.DMA_Mode = DMA_Mode_Circular; // DMA一次模式
DMA_InitStructure.DMA_Priority = DMA_Priority_Medium; // 优先级:中
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable; // 禁止内存到内存的传输
DMA_Init(DMA1_Channel5, &DMA_InitStructure); // 配置DMA通道DMA1_Channel5
DMA_Cmd(DMA1_Channel5,ENABLE); // 使能DMA
}
void USART1_IRQHandler(void)
{
sig++;
u8 clear=0;
if(USART_GetITStatus(USART1, USART_IT_IDLE) != RESET)
{
clear = USART1->SR;
clear = USART1->DR;
DMA_Config();
}
}
}
2020.4.21于家中,QAQ我要回学校。