LD14激光雷达与STM32F103C8T6(标准库)获取雷达360度数据(1)

1、LD14激光雷达介绍

(1)、LD14激光雷达主要事由测距核心、无线传电单元、无线通讯单元、角度测量单元、电机驱动单元和机械外壳组成。

(2)、LD14激光雷达采用三角测量法技术,可进行每秒2300次的测量。每次测距LD14会从一个固定的角度发射红外光线,激光遇到目标物体后会被反射到接受单元。通过激光、目标物体、接受单元形参三角关系、从而解算出距离数据后,LD14会把获取到的距离数据结合角度测量单元测量到的角度值组成点云数据。再把数据发送到外部接口。电机驱动单元会驱动电机,可用PWM控制到指定转速,默认转速为6HZ,输入PWM频率为15-30K,推荐24K;占空比在(45%,55%区间内,不包含45%与55%),且最少100ms持续时间。注:不使用外部控速,必须将PWM引脚接地或悬空。

(3)、角度分辨率为1度,测量的最大量程8米,最小量程为15厘米。

如图所示:

图片如下(整体框图):

(我的工位哈哈哈哈)

视频如下:

激光雷达工作视频

LD14激光雷达外形与接口:

LD14的数据通讯采用标准异步串口(UART)单向发送,数据参数如下表所示,而且LD14采用单向通讯,上电稳定后,便开始发送测量数据,不需要发送任何指令

LD14使用左手坐标系,选择中心为坐标原点,选择中心与主动轮中心连线方向为零度方向,旋转角度沿顺时针方向增大,如图所示:

 2、LD激光雷达通讯协议

一、数据包格式
LD14 采用单向通讯,稳定工作后,即开始发送测量数据包,不需要发送任何指令。测量数据包格式如下图所示。


每个测量数据点由 2 个字节长度的距离值和 1 个字节长度的置信度值组成,如下图所示:

距离值的单位为 mm。信号强度值反映的是光反射强度,强度越高,信号强度值越大;强度越低,信号强度值越小。每个点的角度值是通过起始角度和结束角度线性插值得来,其角度计算方法:

step = (end_angle – start_angle)/(len – 1);
angle = start_angle + step*i;
其中 len 为一个数据包的测量点数,i 的取值范围为[0 , len )

雷达使用的是串口通信,波特率为115200dps,(每一个数据包输出47个字节的数据),输出协议具体情况如下:

1、Byte_0:为帧头,固定为 0x54。

2、Byte_1:为表示帧类型,目前固定为 1,低五位表示一个包的测量点数, 目前固定为 12,所以改字节固定为 0x2C。

3、Byte_2-Byte_3:雷达转速,单位为度每秒,低八位在前,例如Speed_L=0x68,Speed_H=0x08

为0x0868=2512度/s。

4、Byte_4-Byte_5:一帧数据的起始角度,低位在前,是实际角度的 100 倍,例如:Start_Angle

=0xAB,Start_Angle_H=0x7E,即 0x7EAB=32427(10进制)=324.27 度

 5、Byte_6-Byte_41:点云数据:每个数据包括 2 字节距离和 1 字节强度信息。低位在前,距离

为mm例 如 : Distance_1_L=0x64 , Distance_1_H=0X00 ,PEAK_1=0x64,表示距离0x64=10

0mm,强度100。(要转换成10进制)0x64=01100100(二进制)64+32+4=100(复习哈进制算法哈哈哈)

6、Byte_42-Byte_43:一帧数据的结束角度,低位在前,是实际角度的 100 倍,例如Stop_Angle

_L=0xBE,Stop_Angle_H=0x82,即 0x82BE=33470=334.70 度。

7、Byte_44-Byte_45:时间戳,单位为 ms,最大为 30000,到达 30000 会重新开始计数。

8、Byte46:从 Byte_0 到 Byte_45 数据和校验值。CRC = byte0+byte1+…+byte56。

参考数据案例分析(重点):

LD14激光雷达的数据角度分辨率是 1 度,所以雷达转一圈那么会输出 360 个数据,但雷达一包数据包输出的点是 12 个点,按此可知,雷达一圈能输出差不多 30 个数据包,输出一包数据包的角度范围大概是 12 度(Byte_6-Byte_41(一共36个字节除以3个字节=12度)也就是说一个数据包传递12度的角度与距离)。雷达接上串口后会自动 以波特率 115200 发送数据包,不需要发送其他命令。数据包之间间隔一个点的角度,也就是角度分辨率 1 度。以下是使用串口助手接收到的数据,可以看出[54 2C 68 08 BE 82 E5 00 E8 D7 00 E4 D8 00 E1 D1 00 E4 D3 00 E8 D3 00 E4 CD 01 E7 C1 00 E4 C4 00 E0 C0 00 E2 C0 00 E1 C0 00 15 CE 86 3A 1A 50]其中的一个数据包。我们对其进行解析。

1.帧头和数据帧长度

帧头 1 个字节,固定值是 0X54。 数据帧长度也是固定的,值为 0X2C,单位为字节,即 47 字节。

2.转速

分析捕获到的转速信息[68 08],即 0X0868= 2152 度/s。

3.起始角度和结束角度

角度信息是放大了 100 倍的信息,如捕获到的起始角度信息[BE 82],即=0X82BE = 33470 = 334.70 度;结束角度信息[CE 86],即 0X86CE =34510 = 345.10度

4.点云数据

一包数据包会输出 12 个点的数据,每个点的数据包含距离和强度信息。比 如捕获到的第一个点云数据[E5 0 E8],可以知道距离是 0X00E5=229mm,强度为 0XE8=232。

5.校验和

校验和是前面所有数据相加的结果,只要 8 位数据。 例如数据为:54 2C 68 08 AB 7E E0 00 E4 DC 00 E2 D9 00 E5 D5 00 E3 D3 00 E4 D0 00 E9 CD 00 E4 CA 00 E2 C7 00 E9 C5 00 E5 C2 00 E5 C0 00 E5 BE 82 3A 1A 这 46 个数据我们可以经过下面的代码来计算得出 50 这个结果。

CRC校验计算方式如下:

static const uint8_t CrcTable[256] ={
0x00, 0x4d, 0x9a, 0xd7, 0x79, 0x34, 0xe3,
0xae, 0xf2, 0xbf, 0x68, 0x25, 0x8b, 0xc6, 0x11, 0x5c, 0xa9, 0xe4, 0x33,
0x7e, 0xd0, 0x9d, 0x4a, 0x07, 0x5b, 0x16, 0xc1, 0x8c, 0x22, 0x6f, 0xb8,
0xf5, 0x1f, 0x52, 0x85, 0xc8, 0x66, 0x2b, 0xfc, 0xb1, 0xed, 0xa0, 0x77,
0x3a, 0x94, 0xd9, 0x0e, 0x43, 0xb6, 0xfb, 0x2c, 0x61, 0xcf, 0x82, 0x55,
0x18, 0x44, 0x09, 0xde, 0x93, 0x3d, 0x70, 0xa7, 0xea, 0x3e, 0x73, 0xa4,
0xe9, 0x47, 0x0a, 0xdd, 0x90, 0xcc, 0x81, 0x56, 0x1b, 0xb5, 0xf8, 0x2f,
0x62, 0x97, 0xda, 0x0d, 0x40, 0xee, 0xa3, 0x74, 0x39, 0x65, 0x28, 0xff,
0xb2, 0x1c, 0x51, 0x86, 0xcb, 0x21, 0x6c, 0xbb, 0xf6, 0x58, 0x15, 0xc2,
0x8f, 0xd3, 0x9e, 0x49, 0x04, 0xaa, 0xe7, 0x30, 0x7d, 0x88, 0xc5, 0x12,
0x5f, 0xf1, 0xbc, 0x6b, 0x26, 0x7a, 0x37, 0xe0, 0xad, 0x03, 0x4e, 0x99,
0xd4, 0x7c, 0x31, 0xe6, 0xab, 0x05, 0x48, 0x9f, 0xd2, 0x8e, 0xc3, 0x14,
0x59, 0xf7, 0xba, 0x6d, 0x20, 0xd5, 0x98, 0x4f, 0x02, 0xac, 0xe1, 0x36,
0x7b, 0x27, 0x6a, 0xbd, 0xf0, 0x5e, 0x13, 0xc4, 0x89, 0x63, 0x2e, 0xf9,
0xb4, 0x1a, 0x57, 0x80, 0xcd, 0x91, 0xdc, 0x0b, 0x46, 0xe8, 0xa5, 0x72,
0x3f, 0xca, 0x87, 0x50, 0x1d, 0xb3, 0xfe, 0x29, 0x64, 0x38, 0x75, 0xa2,
0xef, 0x41, 0x0c, 0xdb, 0x96, 0x42, 0x0f, 0xd8, 0x95, 0x3b, 0x76, 0xa1,
0xec, 0xb0, 0xfd, 0x2a, 0x67, 0xc9, 0x84, 0x53, 0x1e, 0xeb, 0xa6, 0x71,
0x3c, 0x92, 0xdf, 0x08, 0x45, 0x19, 0x54, 0x83, 0xce, 0x60, 0x2d, 0xfa,
0xb7, 0x5d, 0x10, 0xc7, 0x8a, 0x24, 0x69, 0xbe, 0xf3, 0xaf, 0xe2, 0x35,
0x78, 0xd6, 0x9b, 0x4c, 0x01, 0xf4, 0xb9, 0x6e, 0x23, 0x8d, 0xc0, 0x17,
0x5a, 0x06, 0x4b, 0x9c, 0xd1, 0x7f, 0x32, 0xe5, 0xa8
};
uint8_t CalCRC8(uint8_t *p, uint8_t len){
uint8_t crc = 0;
uint16_t i;
for (i = 0; i < len; i++){
crc = CrcTable[(crc ^ *p++) & 0xff];
}
return crc;
}
3、STM32与LD14联动(终于到正题了)

其实问题最大就是如何处理16进制数据,毕竟传回来的不是10进制完整的长度与角度,我们可以借助官方给的示例伪代码进行二次修改。

1、串口(设置双串口,一个接收雷达数据(PA3),另外一个打印在上位机(PA9,PA10))

的哈斯的

#include "usart.h"
#include "stm32f10x.h"
#include <stdio.h>

void My_USART2_Init(void)  
{  
    GPIO_InitTypeDef GPIO_InitStrue;  
    USART_InitTypeDef USART_InitStrue;  
    NVIC_InitTypeDef NVIC_InitStrue;  
      
    RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA,ENABLE);//GPIO端口使能  
    RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2,ENABLE);//串口端口使能  
      
    GPIO_InitStrue.GPIO_Mode=GPIO_Mode_AF_PP;  
    GPIO_InitStrue.GPIO_Pin=GPIO_Pin_2;  
    GPIO_InitStrue.GPIO_Speed=GPIO_Speed_10MHz;  
    GPIO_Init(GPIOA,&GPIO_InitStrue);  
      
    GPIO_InitStrue.GPIO_Mode=GPIO_Mode_IN_FLOATING;  
    GPIO_InitStrue.GPIO_Pin=GPIO_Pin_3;  
    GPIO_InitStrue.GPIO_Speed=GPIO_Speed_10MHz;  
    GPIO_Init(GPIOA,&GPIO_InitStrue);  
      
    USART_InitStrue.USART_BaudRate=115200;  
    USART_InitStrue.USART_HardwareFlowControl=USART_HardwareFlowControl_None;  
    USART_InitStrue.USART_Mode=USART_Mode_Tx|USART_Mode_Rx;  
    USART_InitStrue.USART_Parity=USART_Parity_No;  
    USART_InitStrue.USART_StopBits=USART_StopBits_1;  
    USART_InitStrue.USART_WordLength=USART_WordLength_8b;  
      
    USART_Init(USART2,&USART_InitStrue);
      
    USART_Cmd(USART2,ENABLE);					//使能串口2  
      
    USART_ITConfig(USART2,USART_IT_RXNE,ENABLE);//开启接收中断  
      
    NVIC_InitStrue.NVIC_IRQChannel=USART2_IRQn;  
    NVIC_InitStrue.NVIC_IRQChannelCmd=ENABLE;  
    NVIC_InitStrue.NVIC_IRQChannelPreemptionPriority=0;  
    NVIC_InitStrue.NVIC_IRQChannelSubPriority=1;  
    NVIC_Init(&NVIC_InitStrue);  
      
}  




void usart_init(void){

	
	GPIO_InitTypeDef GPIO_programe;
	USART_InitTypeDef USART_programe;
  NVIC_InitTypeDef NVIC_programe;//所有的中断都要用到NVIC,不过不同中断要求不同
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, ENABLE);
RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE);

	
	
 GPIO_programe.GPIO_Mode=GPIO_Mode_AF_PP;
	GPIO_programe.GPIO_Pin=GPIO_Pin_9;
	GPIO_programe.GPIO_Speed=GPIO_Speed_50MHz;
	GPIO_Init(GPIOA, &GPIO_programe);

	

	GPIO_programe.GPIO_Mode=GPIO_Mode_IN_FLOATING;
	GPIO_programe.GPIO_Pin=GPIO_Pin_10;
	GPIO_programe.GPIO_Speed=GPIO_Speed_50MHz;
	GPIO_Init(GPIOA, &GPIO_programe);
	
	
	USART_programe.USART_BaudRate=115200;
	USART_programe.USART_HardwareFlowControl=USART_HardwareFlowControl_None;
	USART_programe.USART_Mode=USART_Mode_Rx|USART_Mode_Tx;
	USART_programe.USART_Parity=USART_Parity_No;
	USART_programe.USART_StopBits=USART_StopBits_1;
	USART_programe.USART_WordLength=USART_WordLength_8b;
	USART_Init(USART1, &USART_programe);
		  USART_ITConfig(USART1, USART_IT_RXNE, ENABLE);//很重要是串口中断的打开
		USART_Cmd(USART1, ENABLE);//比GPIO多一步,这个是对串口使能
	
	
	NVIC_programe.NVIC_IRQChannel=USART1_IRQn;//为中断源,不可写成,因为系统也不会报错,中断通道
                                         //因为这里是串口中断,所以要用USART中断,之前LED是exti,因为那个代表GPIO了,这里不同,这里是串口中断
	NVIC_programe.NVIC_IRQChannelCmd=ENABLE;
	NVIC_programe.NVIC_IRQChannelPreemptionPriority=2;
	NVIC_programe.NVIC_IRQChannelSubPriority=2;
	NVIC_Init(&NVIC_programe);

}

void USART_send_byte(USART_TypeDef* USARTx, uint16_t Data){
   USART_SendData(USARTx, Data);
  while( USART_GetFlagStatus(USARTx, USART_FLAG_TXE)==RESET);

}

//发送字符串->要调用上面的函数
void USART_send_str(USART_TypeDef* USARTx, char *str){
	uint16_t i=0;//无符号16位,等同于unsigned,所以就是一个无符号的整数
	do{
	USART_send_byte(USARTx, *(str+i));
	i++;
	
	}while(*(str+i)!='\0');
	
 while(USART_GetFlagStatus(USARTx, USART_FLAG_TC)==RESET);

}

int fputc(int ch, FILE *f){
    USART_SendData(USART1, (uint8_t)ch);//定义一个无符号字符,否则会出问题
    while( USART_GetFlagStatus(USART1, USART_FLAG_TXE)==RESET);
   return ch;
}



int fgetc(FILE *f){//类似于输入

   while( USART_GetFlagStatus(USART1, USART_FLAG_RXNE)==RESET);//USART_FLAG_RXNE是判断是否接受数据寄存器非空标志--就是和TEX相对,这里是收
	return (int)USART_ReceiveData(USART1);//这个也是收usart.h的文件,强转int,返回收取的东西
}









2、PWM控速(可要可不要,我刚刚开始用了,后面发现处理太慢,就接地了)

#include "pwm.h"
#include "stm32f10x.h"



void pwm_Init(void){
      GPIO_InitTypeDef gpio_init_progrme;
	TIM_TimeBaseInitTypeDef tme_init_progrme;
	TIM_OCInitTypeDef pwm_init_progrme;
	
  
RCC_APB2PeriphClockCmd( RCC_APB2Periph_GPIOB, ENABLE);
	
  RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3 ,  ENABLE);
		RCC_APB2PeriphClockCmd( RCC_APB2Periph_AFIO, ENABLE);
  GPIO_PinRemapConfig(GPIO_PartialRemap_TIM3 ,  ENABLE);//重映射
	
  gpio_init_progrme.GPIO_Mode=GPIO_Mode_AF_PP;
	gpio_init_progrme.GPIO_Pin=GPIO_Pin_5;
	gpio_init_progrme.GPIO_Speed=GPIO_Speed_50MHz;
  GPIO_Init(GPIOB, &gpio_init_progrme);
	


  tme_init_progrme.TIM_ClockDivision=TIM_CKD_DIV1;
	tme_init_progrme.TIM_CounterMode=TIM_CounterMode_Up;
	tme_init_progrme.TIM_Period=3000-1;//ARR,也就是周期
	tme_init_progrme.TIM_Prescaler=0;
  TIM_TimeBaseInit(TIM3, &tme_init_progrme );
		  
	
	pwm_init_progrme.TIM_OutputState=TIM_OutputState_Enable;//使能
	pwm_init_progrme.TIM_OCMode=TIM_OCMode_PWM1;
	pwm_init_progrme.TIM_OCPolarity=TIM_OCPolarity_Low;
   TIM_OC2Init(TIM3, &pwm_init_progrme);//TIM3的二通道,所以后面的compare2,表示通道2
   TIM_OC2PreloadConfig( TIM3, TIM_OCPreload_Enable );
 TIM_Cmd( TIM3, ENABLE);//一个就可以了,因为是使能TIM3,pwm也是TIM的一部分,所以一个就够了
	
	
}

3、LED灯(喜欢就用)

#include "led.h"
#include "stm32f10x.h"
void led_init(void){

  GPIO_InitTypeDef led_show;
  RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC, ENABLE);

  led_show.GPIO_Mode=GPIO_Mode_Out_PP;
  led_show.GPIO_Pin=GPIO_Pin_13;
  led_show.GPIO_Speed=GPIO_Speed_10MHz;
  GPIO_Init(GPIOC, &led_show);
	
}

4、main函数

#include "stm32f10x.h"
#include "main.h"
#include "usart.h"
#include <stdio.h>
#include "led.h"
#include "pwm.h"
#include "systick.h"
#include "stdio.h"
#include "string.h"



/*
LD14 雷达的数据角度分辨率是 1 度,所以雷达转一圈那么会输出 360 个数
据,但雷达一包数据包输出的点是 12 个点,按此可知,雷达一圈能输出差不多
30 个数据包,输出一包数据包的角度范围大概是 12 度。

*/




#define HEADER 0x54
#define POINT_PER_PACK 12
#define LENGTH  	0x2C 	//低五位是一帧数据接收到的点数,目前固定是12,高三位预留

//CRC 校验计算方式如下:
static const uint8_t CrcTable[256] ={
0x00, 0x4d, 0x9a, 0xd7, 0x79, 0x34, 0xe3,
0xae, 0xf2, 0xbf, 0x68, 0x25, 0x8b, 0xc6, 0x11, 0x5c, 0xa9, 0xe4, 0x33,
0x7e, 0xd0, 0x9d, 0x4a, 0x07, 0x5b, 0x16, 0xc1, 0x8c, 0x22, 0x6f, 0xb8,
0xf5, 0x1f, 0x52, 0x85, 0xc8, 0x66, 0x2b, 0xfc, 0xb1, 0xed, 0xa0, 0x77,
0x3a, 0x94, 0xd9, 0x0e, 0x43, 0xb6, 0xfb, 0x2c, 0x61, 0xcf, 0x82, 0x55,
0x18, 0x44, 0x09, 0xde, 0x93, 0x3d, 0x70, 0xa7, 0xea, 0x3e, 0x73, 0xa4,
0xe9, 0x47, 0x0a, 0xdd, 0x90, 0xcc, 0x81, 0x56, 0x1b, 0xb5, 0xf8, 0x2f,
0x62, 0x97, 0xda, 0x0d, 0x40, 0xee, 0xa3, 0x74, 0x39, 0x65, 0x28, 0xff,
0xb2, 0x1c, 0x51, 0x86, 0xcb, 0x21, 0x6c, 0xbb, 0xf6, 0x58, 0x15, 0xc2,
0x8f, 0xd3, 0x9e, 0x49, 0x04, 0xaa, 0xe7, 0x30, 0x7d, 0x88, 0xc5, 0x12,
0x5f, 0xf1, 0xbc, 0x6b, 0x26, 0x7a, 0x37, 0xe0, 0xad, 0x03, 0x4e, 0x99,
0xd4, 0x7c, 0x31, 0xe6, 0xab, 0x05, 0x48, 0x9f, 0xd2, 0x8e, 0xc3, 0x14,
0x59, 0xf7, 0xba, 0x6d, 0x20, 0xd5, 0x98, 0x4f, 0x02, 0xac, 0xe1, 0x36,
0x7b, 0x27, 0x6a, 0xbd, 0xf0, 0x5e, 0x13, 0xc4, 0x89, 0x63, 0x2e, 0xf9,
0xb4, 0x1a, 0x57, 0x80, 0xcd, 0x91, 0xdc, 0x0b, 0x46, 0xe8, 0xa5, 0x72,
0x3f, 0xca, 0x87, 0x50, 0x1d, 0xb3, 0xfe, 0x29, 0x64, 0x38, 0x75, 0xa2,
0xef, 0x41, 0x0c, 0xdb, 0x96, 0x42, 0x0f, 0xd8, 0x95, 0x3b, 0x76, 0xa1,
0xec, 0xb0, 0xfd, 0x2a, 0x67, 0xc9, 0x84, 0x53, 0x1e, 0xeb, 0xa6, 0x71,
0x3c, 0x92, 0xdf, 0x08, 0x45, 0x19, 0x54, 0x83, 0xce, 0x60, 0x2d, 0xfa,
0xb7, 0x5d, 0x10, 0xc7, 0x8a, 0x24, 0x69, 0xbe, 0xf3, 0xaf, 0xe2, 0x35,
0x78, 0xd6, 0x9b, 0x4c, 0x01, 0xf4, 0xb9, 0x6e, 0x23, 0x8d, 0xc0, 0x17,
0x5a, 0x06, 0x4b, 0x9c, 0xd1, 0x7f, 0x32, 0xe5, 0xa8
};
uint8_t CalCRC8(uint8_t *p, uint8_t len){
uint8_t crc = 0;
uint16_t i;
for (i = 0; i < len; i++){
crc = CrcTable[(crc ^ *p++) & 0xff];
}
return crc;
}



typedef struct __attribute__((packed)) Point_Data
{
	uint16_t distance;//距离
	uint8_t confidence;//置信度
	
}LidarPointStructDef;

typedef struct __attribute__((packed)) Pack_Data
{
	uint8_t header;
	uint8_t ver_len;
	uint16_t speed;
	uint16_t start_angle;
	LidarPointStructDef point[POINT_PER_PACK];
	uint16_t end_angle;
	uint16_t timestamp;
	uint8_t crc8;
}LiDARFrameTypeDef;
typedef struct __attribute__((packed)) PointDataProcess_
{
	uint16_t distance;//角度
	float angle;//距离
}PointDataProcessDef;//经过处理后的数据

LiDARFrameTypeDef Pack_Data;			//雷达接收的数据储存在这个变量之中
PointDataProcessDef AvoidData[360];

int count;




int data_process(void)
{
		float average_angel;				//定义一帧数据平均角度

	static uint16_t data_cnt_avoid = 0;		//避障模式数组计数变量
	
	//	static uint8_t data_cnt_avoid = 0;		//范围0-255,这个bug解决了一下午

	
	uint8_t i = 0;
	float start_angle = Pack_Data.start_angle/100.0;//计算一帧16个点的开始角度
	float end_angel = Pack_Data.end_angle/100.0;	//结束角度

	
	if(start_angle>=360)
	{
	start_angle -= 360;

	}
		if(end_angel>=360)
		{	

			end_angel -= 360;

	}

	
	
	if(start_angle>end_angel)
	{
		end_angel +=360;
	}	
	average_angel = (end_angel - start_angle)/12;

		for(i=0;i<12;i++)
		{
			AvoidData[data_cnt_avoid].angle = start_angle + i*average_angel;

			AvoidData[data_cnt_avoid].distance = Pack_Data.point[i].distance;
		//	printf("data_cnt_avoid = %d/r/n",data_cnt_avoid); 重大发现这个到225就会没有数据了,why?,
		//我晓得了,我数据类型坐小了,不能用uint8_t,只能到225,cnm,搞了一下午
			if(++data_cnt_avoid == 360)
				data_cnt_avoid = 0;
		}
	//}
	return 0;
	
}


 





int  main()
{
		int i;

	
  usart_init();
  led_init();
	NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);
  My_USART2_Init();  
  pwm_Init();
  TIM_SetCompare2( TIM3, 1350);

	
while (1)
  {
      
		printf("接收成功%d\r\n",count);
		
		for(i=0;i<360;i++)
		{
			printf("角度:%f 度,距离:%d mm\r\n",AvoidData[i].angle,AvoidData[i].distance); //一共是360度,距离是mm

		}
							

 
  }
	

}





void USART2_IRQHandler(void)//接收ld14雷达数据,一帧47个字节
{
		u8 temp_data;//换成数组

	static u8 state = 0;//状态位	,指示当前数据帧的位置
	static u8 crc = 0;	//校验和
	static u8 cnt = 0;	//用于一帧12个点的计数
	

	
	if(USART_GetITStatus(USART2, USART_IT_RXNE) != RESET) //接收到数据
	{	
    USART_ClearITPendingBit(USART2,USART_IT_RXNE);		
		temp_data=USART_ReceiveData(USART2);                  //在这里全部接收,接受完了,再处理,用数组接受



		if (state > 5)	
		{
			if(state < 42)
			{
				if(state%3 == 0)		//一帧数据中的序号为6,9.....39的数据,距离值低8位
				{
					Pack_Data.point[cnt].distance = (u16)temp_data;       //point[cnt]为12个大小的数组
					state++;
					crc = CrcTable[(crc^temp_data) & 0xff];
				}
				else if(state%3 == 1)	//一帧数据中的序号为7,10.....40的数据,距离值高8位
				{
					Pack_Data.point[cnt].distance = ((u16)temp_data<<8)+Pack_Data.point[cnt].distance;
					state++;
					crc = CrcTable[(crc^temp_data) & 0xff];
				}
				else					//一帧数据中的序号为8,11.....41的数据,置信度
				{
					Pack_Data.point[cnt].confidence = temp_data;
					cnt++;	
					state++;
					crc = CrcTable[(crc^temp_data) & 0xff];
				}
			}
			else 
			{
				switch(state)
				{
					case 42:
						Pack_Data.end_angle = (u16)temp_data;						//结束角度低8位
						state++;
						crc = CrcTable[(crc^temp_data) & 0xff];
						break;
					case 43:
						Pack_Data.end_angle = ((u16)temp_data<<8)+Pack_Data.end_angle;//结束角度高8位
						state++;
						crc = CrcTable[(crc^temp_data) & 0xff];
						break;
					case 44:
						Pack_Data.timestamp = (u16)temp_data;						//时间戳低8位
						state++;
						crc = CrcTable[(crc^temp_data) & 0xff];
						break;
					case 45:
						Pack_Data.timestamp = ((u16)temp_data<<8)+Pack_Data.timestamp;//时间戳高8位
						state++;
						crc = CrcTable[(crc^temp_data) & 0xff];
						break;
					case 46:
						Pack_Data.crc8 = temp_data;		//雷达传来的校验和
						if(Pack_Data.crc8 == crc)		//校验正确
						{
							data_process();				//接收到一帧且校验正确可以进行数据处理
						}
						else
							
						{
							memset(&Pack_Data, 0, sizeof(LiDARFrameTypeDef));//清零
						}
						crc = 0;
						state = 0;
						cnt = 0;//复位
						break;
					default: break;
				}
			}
		}
		else 
		{
			switch(state)
			{
				case 0:
					if(temp_data == HEADER)									//头固定
					{
						Pack_Data.header = temp_data;
						state++;
						crc = CrcTable[(crc^temp_data) & 0xff];				//开始进行校验
					} else state = 0,crc = 0;
					break;
				case 1:
					if(temp_data == LENGTH)									//测量的点数,目前固定
					{
						Pack_Data.ver_len = temp_data;
						state++;
						crc = CrcTable[(crc^temp_data) & 0xff];
					} else state = 0,crc = 0;
					break;
				case 2:
					Pack_Data.speed = (u16)temp_data;						//雷达的转速低8位,单位度每秒
					state++;
					crc = CrcTable[(crc^temp_data) & 0xff];
					break;
				case 3:
					Pack_Data.speed = ((u16)temp_data<<8)+Pack_Data.speed;	//雷达的转速高8位
					state++;
					crc = CrcTable[(crc^temp_data) & 0xff];
					break;
				case 4:
					Pack_Data.start_angle = (u16)temp_data;					//开始角度低8位,放大了100倍
					state++;
					crc = CrcTable[(crc^temp_data) & 0xff];
					break;
				case 5:
					Pack_Data.start_angle = ((u16)temp_data<<8)+Pack_Data.start_angle;
					state++;
					crc = CrcTable[(crc^temp_data) & 0xff];
					break;
				default: break;
			}
		}

	}	
} 



:这里有个小乌龙,就是我写存放角度数组,按理来说360度,但我写的uint8_t data_cnt_avoid = 0,这样data_cnt_avoid 就只有uint8_t 的255个数据,最好我上位机一看每次就只有255个有效数据,其余全为0,所以这种细节一定要注意了。

相应的代码已经给出来了,也有注释,要注意的是data_process()这个函数很重要,注意是处理串口接受来的已经由16进制转换为10进制的数据。

预告:还有bug,主要出现在上位机打印与接收数据的速度差上,下一篇博客会进一步优化代码,解决bug。可以先看一下bug,如图所示:

 

  • 8
    点赞
  • 40
    收藏
    觉得还不错? 一键收藏
  • 1
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论 1
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值