ROS上位机与stm32进行串口通信
- 1.1 ROS发送数据
- 1.2 stm32接收数据
- 2.1 stm32发送数据
- 2.2 ROS接收数据
- 上位机串口初始化文件代码
- 下位机stm32的串口配置代码
总代码在文末,需要完整的工程文件可以留个邮箱。
首先创建一个功能包,用于发送和接收数据。
注意:
1.功能包依赖: roscpp std_msgs rosserial
2.当有两个c++文件进行编译时可以在功能包下的CMakeLists.txt文件中
add_executable(publish_node src/publish_node.cpp
src/mbot_linux_serial.cpp)
第一部分是ROS上位机给stm32发送数据。第二部分是stm32给ROS上位机发送数据。下面已经给出每个部分要用到的函数,直接调用即可。第三部分给出完整的stm32与ros上位机的文件代码。
要注意的是共用体的运用
union sendData
{
short d;
unsigned char data[2];
}leftVelNow,rightVelNow,angleNow;
union receiveData
{
short d;
unsigned char data[2];
}leftVelSet,rightVelSet;
用了这个结构就可以让发送的数据扩充到2字节,如果有需要可以更大。
short d 和 unsigned char data[2] 共用一段内存,发送的时候short类型的数据分两次发送出去,接收到后两段数据通过共用体结构体来读取出来。
1.1 ROS发送数据
发送的数据结构
帧数 | 数据 |
---|
第1帧 | 0x55 |
第2帧 | 0xaa |
第3帧 | 发送的有效数据的长度(5字节) |
第4帧 | 数据1 |
第5帧 | 数据1 |
第6帧 | 数据2 |
第7帧 | 数据2 |
第8帧 | 数据3 |
第9帧 | 0x0d |
第10帧 | 0x0a |
void writeSpeed(double Left_v, double Right_v,unsigned char ctrlFlag)
{
unsigned char buf[11] = {0};
int i, length = 0;
leftVelSet.d = Left_v;
rightVelSet.d = Right_v;
for(i = 0; i < 2; i++)
buf[i] = header[i];
length = 5;
buf[2] = length;
for(i = 0; i < 2; i++)
{
buf[i + 3] = leftVelSet.data[i];
buf[i + 5] = rightVelSet.data[i];
}
buf[3 + length - 1] = ctrlFlag;
buf[3 + length] = getCrc8(buf, 3 + length);
buf[3 + length + 1] = ender[0];
buf[3 + length + 2] = ender[1];
boost::asio::write(sp, boost::asio::buffer(buf));
}
1.2 stm32接收数据
利用单片机的串口中断进行接收
void USART1_IRQHandler(void)
{
if(USART_GetITStatus(USART1, USART_IT_RXNE) != RESET)
{
USART_ClearITPendingBit(USART1,USART_IT_RXNE);
usartReceiveOneData(&testRece1,&testRece2,&testRece3);
}
}
八位循环冗余校验函数,用于检验数据是否正确
unsigned char getCrc8(unsigned char *ptr, unsigned short len)
{
unsigned char crc;
unsigned char i;
crc = 0;
while(len--)
{
crc ^= *ptr++;
for(i = 0; i < 8; i++)
{
if(crc&0x01)
crc=(crc>>1)^0x8C;
else
crc >>= 1;
}
}
return crc;
}
单片机的串口一次只能接收一个字节(8位)的数据。而如果需要接收一个完整数据帧,就要对接收函数进行处理。
int usartReceiveOneData(int *p_leftSpeedSet,int *p_rightSpeedSet,unsigned char *p_crtlFlag)
{
unsigned char USART_Receiver = 0;
static unsigned char checkSum = 0;
static unsigned char USARTBufferIndex = 0;
static short j=0,k=0;
static unsigned char USARTReceiverFront = 0;
static unsigned char Start_Flag = START;
static short dataLength = 0;
USART_Receiver = USART_ReceiveData(USART1);
if(Start_Flag == START)
{
if(USART_Receiver == 0xaa)
{
if(USARTReceiverFront == 0x55)
{
Start_Flag = !START;
receiveBuff[0]=header[0];
receiveBuff[1]=header[1];
USARTBufferIndex = 0;
checkSum = 0x00;
}
}
else
{
USARTReceiverFront = USART_Receiver;
}
}
else
{
switch(USARTBufferIndex)
{
case 0:
receiveBuff[2] = USART_Receiver;
dataLength = receiveBuff[2];
USARTBufferIndex++;
break;
case 1:
receiveBuff[j + 3] = USART_Receiver;
j++;
if(j >= dataLength)
{
j = 0;
USARTBufferIndex++;
}
break;
case 2:
receiveBuff[3 + dataLength] = USART_Receiver;
checkSum = getCrc8(receiveBuff, 3 + dataLength);
if (checkSum != receiveBuff[3 + dataLength])
{
printf("Received data check sum error!");
return 0;
}
USARTBufferIndex++;
break;
case 3:
if(k==0)
{
k++;
}
else if (k==1)
{
for(k = 0; k < 2; k++)
{
leftVelSet.data[k] = receiveBuff[k + 3];
rightVelSet.data[k] = receiveBuff[k + 5];
}
*p_leftSpeedSet = (int)leftVelSet.d;
*p_rightSpeedSet = (int)rightVelSet.d;
*p_crtlFlag = receiveBuff[7];
USARTBufferIndex = 0;
USARTReceiverFront = 0;
Start_Flag = START;
checkSum = 0;
dataLength = 0;
j = 0;
k = 0;
}
break;
default:break;
}
}
return 0;
}
2.1 stm32发送数据
void usartSendData(short leftVel, short rightVel,short angle,unsigned char ctrlFlag)
{
unsigned char buf[13] = {0};
int i, length = 0;
leftVelNow.d = leftVel;
rightVelNow.d = rightVel;
angleNow.d = angle;
for(i = 0; i < 2; i++)
buf[i] = header[i];
length = 7;
buf[2] = length;
for(i = 0; i < 2; i++)
{
buf[i + 3] = leftVelNow.data[i];
buf[i + 5] = rightVelNow.data[i];
buf[i + 7] = angleNow.data[i];
}
buf[3 + length - 1] = ctrlFlag;
buf[3 + length] = getCrc8(buf, 3 + length);
buf[3 + length + 1] = ender[0];
buf[3 + length + 2] = ender[1];
USART_Send_String(buf,sizeof(buf));
}
void USART_Send_String(u8 *p,u16 sendSize)
{
static int length =0;
while(length<sendSize)
{
while( !(USART1->SR&(0x01<<7)) );
USART1->DR=*p;
p++;
length++;
}
length =0;
}
2.2 ROS接收数据
bool readSpeed(double &Left_v,double &Right_v,double &Angle,unsigned char &ctrlFlag)
{
char i, length = 0;
unsigned char checkSum;
unsigned char buf[150]={0};
try
{
boost::asio::streambuf response;
boost::asio::read_until(sp, response, "\r\n",err);
copy(istream_iterator<unsigned char>(istream(&response)>>noskipws),
istream_iterator<unsigned char>(),
buf);
}
catch(boost::system::system_error &err)
{
ROS_INFO("read_until error");
}
if (buf[0]!= header[0] || buf[1] != header[1])
{
ROS_ERROR("Received message header error!");
return false;
}
length = buf[2];
checkSum = getCrc8(buf, 3 + length);
if (checkSum != buf[3 + length])
{
ROS_ERROR("Received data check sum error!");
return false;
}
for(i = 0; i < 2; i++)
{
leftVelNow.data[i] = buf[i + 3];
rightVelNow.data[i] = buf[i + 5];
angleNow.data[i] = buf[i + 7];
}
ctrlFlag = buf[9];
Left_v =leftVelNow.d;
Right_v =rightVelNow.d;
Angle =angleNow.d;
return true;
}
上位机串口初始化文件代码
mbot_linux_serial.cpp文件
#include "mbot_linux_serial.h"
using namespace std;
using namespace boost::asio;
boost::asio::io_service iosev;
boost::asio::serial_port sp(iosev, "/dev/ttyUSB0");
boost::system::error_code err;
const unsigned char ender[2] = {0x0d, 0x0a};
const unsigned char header[2] = {0x55, 0xaa};
union sendData
{
short d;
unsigned char data[2];
}leftVelSet,rightVelSet;
union receiveData
{
short d;
unsigned char data[2];
}leftVelNow,rightVelNow,angleNow;
void serialInit()
{
sp.set_option(serial_port::baud_rate(115200));
sp.set_option(serial_port::flow_control(serial_port::flow_control::none));
sp.set_option(serial_port::parity(serial_port::parity::none));
sp.set_option(serial_port::stop_bits(serial_port::stop_bits::one));
sp.set_option(serial_port::character_size(8));
}
void writeSpeed(double Left_v, double Right_v,unsigned char ctrlFlag)
{
unsigned char buf[11] = {0};
int i, length = 0;
leftVelSet.d = Left_v;
rightVelSet.d = Right_v;
for(i = 0; i < 2; i++)
buf[i] = header[i];
length = 5;
buf[2] = length;
for(i = 0; i < 2; i++)
{
buf[i + 3] = leftVelSet.data[i];
buf[i + 5] = rightVelSet.data[i];
}
buf[3 + length - 1] = ctrlFlag;
buf[3 + length] = getCrc8(buf, 3 + length);
buf[3 + length + 1] = ender[0];
buf[3 + length + 2] = ender[1];
boost::asio::write(sp, boost::asio::buffer(buf));
}
bool readSpeed(double &Left_v,double &Right_v,double &Angle,unsigned char &ctrlFlag)
{
char i, length = 0;
unsigned char checkSum;
unsigned char buf[150]={0};
try
{
boost::asio::streambuf response;
boost::asio::read_until(sp, response, "\r\n",err);
copy(istream_iterator<unsigned char>(istream(&response)>>noskipws),
istream_iterator<unsigned char>(),
buf);
}
catch(boost::system::system_error &err)
{
ROS_INFO("read_until error");
}
if (buf[0]!= header[0] || buf[1] != header[1])
{
ROS_ERROR("Received message header error!");
return false;
}
length = buf[2];
checkSum = getCrc8(buf, 3 + length);
if (checkSum != buf[3 + length])
{
ROS_ERROR("Received data check sum error!");
return false;
}
for(i = 0; i < 2; i++)
{
leftVelNow.data[i] = buf[i + 3];
rightVelNow.data[i] = buf[i + 5];
angleNow.data[i] = buf[i + 7];
}
ctrlFlag = buf[9];
Left_v =leftVelNow.d;
Right_v =rightVelNow.d;
Angle =angleNow.d;
return true;
}
unsigned char getCrc8(unsigned char *ptr, unsigned short len)
{
unsigned char crc;
unsigned char i;
crc = 0;
while(len--)
{
crc ^= *ptr++;
for(i = 0; i < 8; i++)
{
if(crc&0x01)
crc=(crc>>1)^0x8C;
else
crc >>= 1;
}
}
return crc;
}
mbot_linux_serial.h文件
#ifndef MBOT_LINUX_SERIAL_H
#define MBOT_LINUX_SERIAL_H
#include <ros/ros.h>
#include <ros/time.h>
#include <geometry_msgs/TransformStamped.h>
#include <tf/transform_broadcaster.h>
#include <nav_msgs/Odometry.h>
#include <boost/asio.hpp>
#include <geometry_msgs/Twist.h>
extern void serialInit();
extern void writeSpeed(double Left_v, double Right_v,unsigned char ctrlFlag);
extern bool readSpeed(double &Left_v,double &Right_v,double &Angle,unsigned char &ctrlFlag);
unsigned char getCrc8(unsigned char *ptr, unsigned short len);
#endif
下位机stm32的串口配置代码
mbotLinuxUsart.c 文件
#include "mbotLinuxUsart.h"
#include "usart.h"
unsigned char receiveBuff[16] = {0};
const unsigned char header[2] = {0x55, 0xaa};
const unsigned char ender[2] = {0x0d, 0x0a};
union sendData
{
short d;
unsigned char data[2];
}leftVelNow,rightVelNow,angleNow;
union receiveData
{
short d;
unsigned char data[2];
}leftVelSet,rightVelSet;
int usartReceiveOneData(int *p_leftSpeedSet,int *p_rightSpeedSet,unsigned char *p_crtlFlag)
{
unsigned char USART_Receiver = 0;
static unsigned char checkSum = 0;
static unsigned char USARTBufferIndex = 0;
static short j=0,k=0;
static unsigned char USARTReceiverFront = 0;
static unsigned char Start_Flag = START;
static short dataLength = 0;
USART_Receiver = USART_ReceiveData(USART1);
if(Start_Flag == START)
{
if(USART_Receiver == 0xaa)
{
if(USARTReceiverFront == 0x55)
{
Start_Flag = !START;
receiveBuff[0]=header[0];
receiveBuff[1]=header[1];
USARTBufferIndex = 0;
checkSum = 0x00;
}
}
else
{
USARTReceiverFront = USART_Receiver;
}
}
else
{
switch(USARTBufferIndex)
{
case 0:
receiveBuff[2] = USART_Receiver;
dataLength = receiveBuff[2];
USARTBufferIndex++;
break;
case 1:
receiveBuff[j + 3] = USART_Receiver;
j++;
if(j >= dataLength)
{
j = 0;
USARTBufferIndex++;
}
break;
case 2:
receiveBuff[3 + dataLength] = USART_Receiver;
checkSum = getCrc8(receiveBuff, 3 + dataLength);
if (checkSum != receiveBuff[3 + dataLength])
{
printf("Received data check sum error!");
return 0;
}
USARTBufferIndex++;
break;
case 3:
if(k==0)
{
k++;
}
else if (k==1)
{
for(k = 0; k < 2; k++)
{
leftVelSet.data[k] = receiveBuff[k + 3];
rightVelSet.data[k] = receiveBuff[k + 5];
}
*p_leftSpeedSet = (int)leftVelSet.d;
*p_rightSpeedSet = (int)rightVelSet.d;
*p_crtlFlag = receiveBuff[7];
USARTBufferIndex = 0;
USARTReceiverFront = 0;
Start_Flag = START;
checkSum = 0;
dataLength = 0;
j = 0;
k = 0;
}
break;
default:break;
}
}
return 0;
}
void usartSendData(short leftVel, short rightVel,short angle,unsigned char ctrlFlag)
{
unsigned char buf[13] = {0};
int i, length = 0;
leftVelNow.d = leftVel;
rightVelNow.d = rightVel;
angleNow.d = angle;
for(i = 0; i < 2; i++)
buf[i] = header[i];
length = 7;
buf[2] = length;
for(i = 0; i < 2; i++)
{
buf[i + 3] = leftVelNow.data[i];
buf[i + 5] = rightVelNow.data[i];
buf[i + 7] = angleNow.data[i];
}
buf[3 + length - 1] = ctrlFlag;
buf[3 + length] = getCrc8(buf, 3 + length);
buf[3 + length + 1] = ender[0];
buf[3 + length + 2] = ender[1];
USART_Send_String(buf,sizeof(buf));
}
void USART_Send_String(u8 *p,u16 sendSize)
{
static int length =0;
while(length<sendSize)
{
while( !(USART1->SR&(0x01<<7)) );
USART1->DR=*p;
p++;
length++;
}
length =0;
}
unsigned char getCrc8(unsigned char *ptr, unsigned short len)
{
unsigned char crc;
unsigned char i;
crc = 0;
while(len--)
{
crc ^= *ptr++;
for(i = 0; i < 8; i++)
{
if(crc&0x01)
crc=(crc>>1)^0x8C;
else
crc >>= 1;
}
}
return crc;
}
mbotLinuxUsart.h 文件
定义了一些发送和接收需要的数据
#include "mbotLinuxUsart.h"
#include "usart.h"
unsigned char receiveBuff[16] = {0};
const unsigned char header[2] = {0x55, 0xaa};
const unsigned char ender[2] = {0x0d, 0x0a};
union sendData
{
short d;
unsigned char data[2];
}leftVelNow,rightVelNow,angleNow;
union receiveData
{
short d;
unsigned char data[2];
}leftVelSet,rightVelSet;
int usartReceiveOneData(int *p_leftSpeedSet,int *p_rightSpeedSet,unsigned char *p_crtlFlag)
{
unsigned char USART_Receiver = 0;
static unsigned char checkSum = 0;
static unsigned char USARTBufferIndex = 0;
static short j=0,k=0;
static unsigned char USARTReceiverFront = 0;
static unsigned char Start_Flag = START;
static short dataLength = 0;
USART_Receiver = USART_ReceiveData(USART1);
if(Start_Flag == START)
{
if(USART_Receiver == 0xaa)
{
if(USARTReceiverFront == 0x55)
{
Start_Flag = !START;
receiveBuff[0]=header[0];
receiveBuff[1]=header[1];
USARTBufferIndex = 0;
checkSum = 0x00;
}
}
else
{
USARTReceiverFront = USART_Receiver;
}
}
else
{
switch(USARTBufferIndex)
{
case 0:
receiveBuff[2] = USART_Receiver;
dataLength = receiveBuff[2];
USARTBufferIndex++;
break;
case 1:
receiveBuff[j + 3] = USART_Receiver;
j++;
if(j >= dataLength)
{
j = 0;
USARTBufferIndex++;
}
break;
case 2:
receiveBuff[3 + dataLength] = USART_Receiver;
checkSum = getCrc8(receiveBuff, 3 + dataLength);
if (checkSum != receiveBuff[3 + dataLength])
{
printf("Received data check sum error!");
return 0;
}
USARTBufferIndex++;
break;
case 3:
if(k==0)
{
k++;
}
else if (k==1)
{
for(k = 0; k < 2; k++)
{
leftVelSet.data[k] = receiveBuff[k + 3];
rightVelSet.data[k] = receiveBuff[k + 5];
}
*p_leftSpeedSet = (int)leftVelSet.d;
*p_rightSpeedSet = (int)rightVelSet.d;
*p_crtlFlag = receiveBuff[7];
USARTBufferIndex = 0;
USARTReceiverFront = 0;
Start_Flag = START;
checkSum = 0;
dataLength = 0;
j = 0;
k = 0;
}
break;
default:break;
}
}
return 0;
}
void usartSendData(short leftVel, short rightVel,short angle,unsigned char ctrlFlag)
{
unsigned char buf[13] = {0};
int i, length = 0;
leftVelNow.d = leftVel;
rightVelNow.d = rightVel;
angleNow.d = angle;
for(i = 0; i < 2; i++)
buf[i] = header[i];
length = 7;
buf[2] = length;
for(i = 0; i < 2; i++)
{
buf[i + 3] = leftVelNow.data[i];
buf[i + 5] = rightVelNow.data[i];
buf[i + 7] = angleNow.data[i];
}
buf[3 + length - 1] = ctrlFlag;
buf[3 + length] = getCrc8(buf, 3 + length);
buf[3 + length + 1] = ender[0];
buf[3 + length + 2] = ender[1];
USART_Send_String(buf,sizeof(buf));
}
void USART_Send_String(u8 *p,u16 sendSize)
{
static int length =0;
while(length<sendSize)
{
while( !(USART1->SR&(0x01<<7)) );
USART1->DR=*p;
p++;
length++;
}
length =0;
}
unsigned char getCrc8(unsigned char *ptr, unsigned short len)
{
unsigned char crc;
unsigned char i;
crc = 0;
while(len--)
{
crc ^= *ptr++;
for(i = 0; i < 8; i++)
{
if(crc&0x01)
crc=(crc>>1)^0x8C;
else
crc >>= 1;
}
}
return crc;
}
uart.c文件
进行串口的初始化
void uart_init(u32 bound)
{
GPIO_InitTypeDef GPIO_InitStructure;
USART_InitTypeDef USART_InitStructure;
NVIC_InitTypeDef NVIC_InitStructure;
RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1|RCC_APB2Periph_GPIOA, ENABLE);
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);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
GPIO_Init(GPIOA, &GPIO_InitStructure);
NVIC_InitStructure.NVIC_IRQChannel = USART1_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority=3 ;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 3;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
USART_InitStructure.USART_BaudRate = bound;
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_Init(USART1, &USART_InitStructure);
USART_ITConfig(USART1, USART_IT_RXNE, ENABLE);
USART_Cmd(USART1, ENABLE);
}
本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)