You can not select more than 25 topics
Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
391 lines
12 KiB
391 lines
12 KiB
#include "insifhtica_QOAR1271.h" |
|
#include "uavcan.h" |
|
#include "custom_data_def.h" |
|
|
|
uint8_t ar1271_data[LIDAR_360_SIZE]; |
|
//static uint8_t data = 0; |
|
//static uint8_t step = 0; |
|
uint16_t ar1271_rev_flag = 0; |
|
|
|
uint32_t last_rev_usart1_tick; |
|
uint32_t last_rev_usart2_tick; |
|
|
|
struct mr72_c{ |
|
uint32_t time_ms; |
|
float range_f; |
|
uint16_t range; |
|
float azimuth; |
|
float vrel; |
|
uint8_t index; |
|
uint8_t rollcount; |
|
uint8_t rcs; |
|
}mr72_c_data; |
|
|
|
uint16_t range_arr[8]; |
|
float last_range; |
|
uint32_t last_time_ms; |
|
uint8_t range_index; |
|
uint8_t index_arr[8]; |
|
void decode_ar1271(char c,uint8_t index); |
|
|
|
bool decode_mr72(int16_t c); |
|
void data_process(void); |
|
void sortA1(uint16_t a[], uint8_t length); |
|
|
|
|
|
extern void parse_ar1271_data(usart_data_t *usart_data) |
|
{ |
|
osSemaphoreAcquire(radar_parse_mutexHandle, 30); |
|
uint8_t buffer_count; |
|
uint8_t buffer[LIDAR_360_SIZE] = {0}; |
|
//uint8_t message_count; |
|
for (int i = 0; i < usart_data->len; i++) |
|
{ |
|
char c = usart_data->data[i]; |
|
if(1){ |
|
decode_mr72(c); |
|
}else{ |
|
decode_ar1271(c,usart_data->usart_instance); |
|
} |
|
} |
|
data_process(); |
|
osSemaphoreRelease(radar_parse_mutexHandle); |
|
} |
|
|
|
void decode_ar1271(char c,uint8_t index){ |
|
static uint8_t buffer_count; |
|
static uint8_t buffer[LIDAR_360_SIZE] = {0}; |
|
static uint8_t message_count; |
|
if ('T' == c) |
|
{ |
|
buffer_count = 0; |
|
} |
|
buffer[buffer_count++] = c; |
|
|
|
if (buffer_count == 2) //判断帧头2 应为前一句已经++ 故2 |
|
{ |
|
if (c != 'H') |
|
{ |
|
buffer_count = 0; |
|
} |
|
} |
|
// we should always read 19 bytes THxxxxxxxxxxxxxxxxC |
|
if (buffer_count >= 20) |
|
{ |
|
buffer_count = 0; |
|
// check if message has right CRC |
|
if (crc_crc8(buffer, 19) == buffer[19]) |
|
{ |
|
|
|
usart_rev_tick = HAL_GetTick(); |
|
proximity_data_t proximity_data = {0}; |
|
proximity_data.d0 = uint16_value(buffer[2], buffer[3]); |
|
proximity_data.d315 = uint16_value(buffer[4], buffer[5]); |
|
proximity_data.d45 = uint16_value(buffer[16], buffer[17]); |
|
|
|
if (index == USART_INSTANCE_U1) |
|
{ |
|
last_rev_usart1_tick = HAL_GetTick(); |
|
if (proximity1_queueHandle != NULL) |
|
{ |
|
osMessageQueuePut(proximity1_queueHandle, &proximity_data, 0, 10); |
|
} |
|
} |
|
else if (index == USART_INSTANCE_U2) |
|
{ |
|
last_rev_usart2_tick = HAL_GetTick(); |
|
if (proximity2_queueHandle != NULL) |
|
{ |
|
osMessageQueuePut(proximity2_queueHandle, &proximity_data, 0, 10); |
|
} |
|
} |
|
} |
|
} |
|
} |
|
bool decode_mr72(int16_t c) |
|
{ |
|
bool ret = false; |
|
static uint8_t decode_state; |
|
static uint8_t data_len = 0; |
|
static int8_t data_cnt; |
|
static int16_t value_b[8]; |
|
int16_t temp = c; |
|
switch (decode_state) |
|
{ |
|
case 0: |
|
if(temp == 0xAA) |
|
decode_state = 1; |
|
break; |
|
case 1: |
|
if(temp == 0xAA){ |
|
decode_state = 2; |
|
} |
|
else |
|
decode_state = 0; |
|
break; |
|
case 2: |
|
if(temp == 0x0c){ |
|
decode_state = 3; |
|
} |
|
else |
|
decode_state = 0; |
|
break; |
|
case 3: |
|
if(temp == 0x07){ |
|
decode_state = 4; |
|
data_len = 8; |
|
} |
|
else |
|
decode_state = 0; |
|
break; |
|
case 4: |
|
data_cnt = 8 - data_len; |
|
if(data_cnt < 7){{ |
|
value_b[data_cnt] = temp; |
|
data_len -= 1; |
|
} |
|
}else{ |
|
decode_state = 5; |
|
} |
|
break; |
|
case 5: |
|
if(temp == 0x55){ |
|
decode_state = 6; |
|
|
|
} |
|
else |
|
decode_state = 0; |
|
break; |
|
case 6: |
|
|
|
if(temp == 0x55){ |
|
mr72_c_data.time_ms = HAL_GetTick(); |
|
mr72_c_data.index = value_b[0]; |
|
mr72_c_data.range_f = (value_b[2] * 256 + value_b[3]) * 0.01; |
|
mr72_c_data.range = uint16_value(value_b[2], value_b[3]); |
|
mr72_c_data.azimuth = (value_b[1] * 256 + value_b[4]) * 0.01 - 90; |
|
mr72_c_data.vrel = (value_b[5] * 256 + value_b[6]) * 0.05 - 35; |
|
mr72_c_data.rollcount = value_b[5] & 0x03; |
|
mr72_c_data.rcs = value_b[7] * 0.5 - 50; |
|
ret = true; |
|
if((last_range - mr72_c_data.range_f > 0.5) || (last_range - mr72_c_data.range_f < -0.5)){ |
|
bool had_index = false; |
|
for(uint8_t i=0; i<range_index; i++){ |
|
if(index_arr[i] == mr72_c_data.index){ |
|
had_index = true; |
|
break; |
|
} |
|
} |
|
last_range = mr72_c_data.range; |
|
if(range_index < 8 && !had_index){ |
|
range_arr[range_index] = mr72_c_data.range; |
|
index_arr[range_index] = mr72_c_data.index; |
|
range_index +=1; |
|
} |
|
} |
|
} |
|
decode_state = 0; |
|
break; |
|
|
|
default: |
|
break; |
|
} |
|
|
|
return ret; |
|
} |
|
|
|
void data_process(void){ |
|
|
|
if(mr72_c_data.time_ms - last_time_ms > 50 || HAL_GetTick() - last_time_ms > 150){ |
|
if(last_time_ms != mr72_c_data.time_ms){ |
|
last_time_ms = mr72_c_data.time_ms; |
|
// gcs().send_text(MAV_SEVERITY_INFO, "a:%d , %d, %d, %d, %d, %d, %d, %d",range_arr[0],range_arr[1],range_arr[2],range_arr[3],range_arr[4],range_arr[5],range_arr[6],range_arr[7]); |
|
sortA1(range_arr,8); |
|
proximity_t data; |
|
data.d315 = range_arr[0]; |
|
data.d0 = range_arr[1]; |
|
data.d45 = range_arr[2]; |
|
data.d90 = range_arr[3]; |
|
data.d135 = range_arr[4]; |
|
data.d180 = range_arr[5]; |
|
data.d225 = range_arr[6]; |
|
data.d270 = range_arr[7]; |
|
if (proximity1_queueHandle != NULL) |
|
{ |
|
osMessageQueuePut(proximity1_queueHandle, &data, 0, 10); |
|
} |
|
for (uint8_t i = 0; i < 8; i++) |
|
{ |
|
range_arr[i] = 4000; |
|
index_arr[i] = 0; |
|
} |
|
|
|
} |
|
range_index = 0; |
|
} |
|
osSemaphoreRelease(radar_parse_mutexHandle); |
|
} |
|
void sortA1(uint16_t a[], uint8_t length){ |
|
uint8_t i, j; |
|
float temp; |
|
for(i = 0; i < length; ++i){ |
|
for(j = i + 1; j < length; ++j){ |
|
a[i] = a[i] == 0? 4000:a[i]; |
|
a[j] = a[j] == 0? 4000:a[j]; |
|
if(a[j] < a[i]){ //如果后一个元素小于前一个元素则交换 |
|
temp = a[i]; |
|
a[i] = a[j]; |
|
a[j] = temp; |
|
} |
|
} |
|
} |
|
|
|
} |
|
static const uint8_t crc8_table[] = { |
|
0x00, 0x07, 0x0e, 0x09, 0x1c, 0x1b, 0x12, 0x15, 0x38, 0x3f, 0x36, 0x31, |
|
0x24, 0x23, 0x2a, 0x2d, 0x70, 0x77, 0x7e, 0x79, 0x6c, 0x6b, 0x62, 0x65, |
|
0x48, 0x4f, 0x46, 0x41, 0x54, 0x53, 0x5a, 0x5d, 0xe0, 0xe7, 0xee, 0xe9, |
|
0xfc, 0xfb, 0xf2, 0xf5, 0xd8, 0xdf, 0xd6, 0xd1, 0xc4, 0xc3, 0xca, 0xcd, |
|
0x90, 0x97, 0x9e, 0x99, 0x8c, 0x8b, 0x82, 0x85, 0xa8, 0xaf, 0xa6, 0xa1, |
|
0xb4, 0xb3, 0xba, 0xbd, 0xc7, 0xc0, 0xc9, 0xce, 0xdb, 0xdc, 0xd5, 0xd2, |
|
0xff, 0xf8, 0xf1, 0xf6, 0xe3, 0xe4, 0xed, 0xea, 0xb7, 0xb0, 0xb9, 0xbe, |
|
0xab, 0xac, 0xa5, 0xa2, 0x8f, 0x88, 0x81, 0x86, 0x93, 0x94, 0x9d, 0x9a, |
|
0x27, 0x20, 0x29, 0x2e, 0x3b, 0x3c, 0x35, 0x32, 0x1f, 0x18, 0x11, 0x16, |
|
0x03, 0x04, 0x0d, 0x0a, 0x57, 0x50, 0x59, 0x5e, 0x4b, 0x4c, 0x45, 0x42, |
|
0x6f, 0x68, 0x61, 0x66, 0x73, 0x74, 0x7d, 0x7a, 0x89, 0x8e, 0x87, 0x80, |
|
0x95, 0x92, 0x9b, 0x9c, 0xb1, 0xb6, 0xbf, 0xb8, 0xad, 0xaa, 0xa3, 0xa4, |
|
0xf9, 0xfe, 0xf7, 0xf0, 0xe5, 0xe2, 0xeb, 0xec, 0xc1, 0xc6, 0xcf, 0xc8, |
|
0xdd, 0xda, 0xd3, 0xd4, 0x69, 0x6e, 0x67, 0x60, 0x75, 0x72, 0x7b, 0x7c, |
|
0x51, 0x56, 0x5f, 0x58, 0x4d, 0x4a, 0x43, 0x44, 0x19, 0x1e, 0x17, 0x10, |
|
0x05, 0x02, 0x0b, 0x0c, 0x21, 0x26, 0x2f, 0x28, 0x3d, 0x3a, 0x33, 0x34, |
|
0x4e, 0x49, 0x40, 0x47, 0x52, 0x55, 0x5c, 0x5b, 0x76, 0x71, 0x78, 0x7f, |
|
0x6a, 0x6d, 0x64, 0x63, 0x3e, 0x39, 0x30, 0x37, 0x22, 0x25, 0x2c, 0x2b, |
|
0x06, 0x01, 0x08, 0x0f, 0x1a, 0x1d, 0x14, 0x13, 0xae, 0xa9, 0xa0, 0xa7, |
|
0xb2, 0xb5, 0xbc, 0xbb, 0x96, 0x91, 0x98, 0x9f, 0x8a, 0x8d, 0x84, 0x83, |
|
0xde, 0xd9, 0xd0, 0xd7, 0xc2, 0xc5, 0xcc, 0xcb, 0xe6, 0xe1, 0xe8, 0xef, |
|
0xfa, 0xfd, 0xf4, 0xf3}; |
|
|
|
uint8_t crc_crc8(const uint8_t *p, uint8_t len) |
|
{ |
|
uint16_t crc = 0x0; |
|
|
|
while (len--) |
|
{ |
|
const uint16_t i = (crc ^ *p++) & 0xFF; |
|
crc = (crc8_table[i] ^ (crc << 8)) & 0xFF; |
|
} |
|
|
|
return crc & 0xFF; |
|
} |
|
|
|
uint16_t uint16_value(uint8_t h_byte, uint8_t l_byte) |
|
{ |
|
return (uint16_t)(h_byte << 8) | l_byte; |
|
} |
|
|
|
void request_QOAR1271_data(void) |
|
{ |
|
uint8_t send_data1[4] = {0x00, 0x11, 0x02, 0x4C}; |
|
uint8_t send_data2[4] = {0x00, 0x31, 0x03, 0xE5}; |
|
uint8_t send_data3[5] = {0x00, 0x52, 0x02, 0x01, 0xDF}; |
|
uint8_t send_data4[5] = {0x00, 0x52, 0x03, 0x03, 0xC4}; |
|
|
|
HAL_UART_Transmit_DMA(&huart1, send_data1, 4); |
|
osDelay(200); |
|
HAL_UART_Transmit_DMA(&huart1, send_data2, 4); |
|
osDelay(200); |
|
HAL_UART_Transmit_DMA(&huart1, send_data3, 5); |
|
osDelay(200); |
|
HAL_UART_Transmit_DMA(&huart1, send_data4, 5); |
|
osDelay(200); |
|
} |
|
|
|
void request_qoar1271_by_step(uint8_t step, uint8_t usart_index) |
|
{ |
|
usart_data_t send_data = {0}; |
|
send_data.usart_instance = usart_index; |
|
if(USART_INSTANCE_U1 == usart_index) |
|
{ |
|
last_rev_usart1_tick = HAL_GetTick(); |
|
} |
|
else if(USART_INSTANCE_U2 == usart_index) |
|
{ |
|
last_rev_usart2_tick = HAL_GetTick(); |
|
} |
|
|
|
switch (step) |
|
{ |
|
case 1: |
|
|
|
send_data.len = 4; |
|
send_data.data[0] = 0x00; |
|
send_data.data[1] = 0x11; |
|
send_data.data[2] = 0x02; |
|
send_data.data[3] = 0x4C; |
|
osMessageQueuePut(usart_send_queueHandle, &send_data, NULL, 0); |
|
break; |
|
case 2: |
|
|
|
send_data.len = 4; |
|
send_data.data[0] = 0x00; |
|
send_data.data[1] = 0x31; |
|
send_data.data[2] = 0x03; |
|
send_data.data[3] = 0xE5; |
|
osMessageQueuePut(usart_send_queueHandle, &send_data, NULL, 0); |
|
break; |
|
case 3: |
|
|
|
send_data.len = 5; |
|
send_data.data[0] = 0x00; |
|
send_data.data[1] = 0x52; |
|
send_data.data[2] = 0x02; |
|
send_data.data[3] = 0x01; |
|
send_data.data[4] = 0xDF; |
|
osMessageQueuePut(usart_send_queueHandle, &send_data, NULL, 0); |
|
break; |
|
case 4: |
|
|
|
send_data.len = 5; |
|
send_data.data[0] = 0x00; |
|
send_data.data[1] = 0x52; |
|
send_data.data[2] = 0x03; |
|
send_data.data[3] = 0x03; |
|
send_data.data[4] = 0xC4; |
|
osMessageQueuePut(usart_send_queueHandle, &send_data, NULL, 0); |
|
break; |
|
default: |
|
break; |
|
} |
|
} |
|
|
|
void deal_send_data(usart_data_t *rev_data) |
|
{ |
|
|
|
if ((rev_data->data[0] == 0x00) && |
|
(rev_data->data[1] == 0x11) && |
|
(rev_data->data[2] == 0x02) && |
|
(rev_data->data[3] == 0x4C)) |
|
{ |
|
request_qoar1271_by_step(2, rev_data->usart_instance); |
|
} |
|
else if ((rev_data->data[0] == 0x00) && |
|
(rev_data->data[1] == 0x31) && |
|
(rev_data->data[2] == 0x03) && |
|
(rev_data->data[3] == 0xE5)) |
|
{ |
|
request_qoar1271_by_step(3, rev_data->usart_instance); |
|
} |
|
else if ((rev_data->data[0] == 0x00) && |
|
(rev_data->data[1] == 0x52) && |
|
(rev_data->data[2] == 0x02) && |
|
(rev_data->data[3] == 0x01) ) |
|
{ |
|
request_qoar1271_by_step(4, rev_data->usart_instance); |
|
} |
|
else if ((rev_data->data[0] == 0x00) && |
|
(rev_data->data[1] == 0x52) && |
|
(rev_data->data[2] == 0x03) && |
|
(rev_data->data[3] == 0x03) ) |
|
{ |
|
} |
|
}
|
|
|