update seasky doc

This commit is contained in:
NeoZng 2022-11-11 22:23:17 +08:00
parent 33e10fa687
commit 55e12955b7
9 changed files with 118 additions and 42 deletions

View File

@ -25,6 +25,8 @@ static void USARTServiceInit(usart_instance *_instance)
{
HAL_UARTEx_ReceiveToIdle_DMA(_instance->usart_handle, _instance->recv_buff, _instance->recv_buff_size);
// 关闭dma half transfer中断防止两次进入HAL_UARTEx_RxEventCallback()
// 这是HAL库的一个设计失误,发生DMA传输完成/半完成以及串口IDLE中断都会触发HAL_UARTEx_RxEventCallback()
// 我们只希望处理因此直接关闭DMA半传输中断第一种和第三种情况
__HAL_DMA_DISABLE_IT(_instance->usart_handle->hdmarx, DMA_IT_HT);
}
@ -45,8 +47,14 @@ void USARTSend(usart_instance *_instance, uint8_t *send_buf, uint16_t send_size)
* @brief dma/idle中断发生时.uart实例会调用对应的回调进行进一步的处理
* ://
*
* @todo neozng给HAL库的github repo提了issue, ST在最新的一次更新中为此提供了一个HAL_UARTEx_GetRxEventType()
*
*
* @note because DMA half transfer iterrupt(DMA_IT_HT) would call this callback function too, so we just
* disable it when transfer complete using macro: __HAL_DMA_DISABLE_IT(huart->hdmarx,DMA_IT_HT)
* dma half transfer中断防止两次进入HAL_UARTEx_RxEventCallback()
* HAL库的一个设计失误,DMA传输完成/IDLE中断都会触发HAL_UARTEx_RxEventCallback()
* DMA半传输中断第一种和第三种情况
*
* @param huart uart handle indicate which uart is being handled
* @param Size not used temporarily,,

View File

@ -82,30 +82,29 @@ static void BMI088_read_muli_reg(uint8_t reg, uint8_t *buf, uint8_t len);
#endif
static uint8_t write_BMI088_accel_reg_data_error[BMI088_WRITE_ACCEL_REG_NUM][3] =
{
{BMI088_ACC_PWR_CTRL, BMI088_ACC_ENABLE_ACC_ON, BMI088_ACC_PWR_CTRL_ERROR},
{BMI088_ACC_PWR_CONF, BMI088_ACC_PWR_ACTIVE_MODE, BMI088_ACC_PWR_CONF_ERROR},
{BMI088_ACC_CONF, BMI088_ACC_NORMAL | BMI088_ACC_800_HZ | BMI088_ACC_CONF_MUST_Set, BMI088_ACC_CONF_ERROR},
{BMI088_ACC_RANGE, BMI088_ACC_RANGE_6G, BMI088_ACC_RANGE_ERROR},
{BMI088_INT1_IO_CTRL, BMI088_ACC_INT1_IO_ENABLE | BMI088_ACC_INT1_GPIO_PP | BMI088_ACC_INT1_GPIO_LOW, BMI088_INT1_IO_CTRL_ERROR},
{BMI088_INT_MAP_DATA, BMI088_ACC_INT1_DRDY_INTERRUPT, BMI088_INT_MAP_DATA_ERROR}
{
{BMI088_ACC_PWR_CTRL, BMI088_ACC_ENABLE_ACC_ON, BMI088_ACC_PWR_CTRL_ERROR},
{BMI088_ACC_PWR_CONF, BMI088_ACC_PWR_ACTIVE_MODE, BMI088_ACC_PWR_CONF_ERROR},
{BMI088_ACC_CONF, BMI088_ACC_NORMAL | BMI088_ACC_800_HZ | BMI088_ACC_CONF_MUST_Set, BMI088_ACC_CONF_ERROR},
{BMI088_ACC_RANGE, BMI088_ACC_RANGE_6G, BMI088_ACC_RANGE_ERROR},
{BMI088_INT1_IO_CTRL, BMI088_ACC_INT1_IO_ENABLE | BMI088_ACC_INT1_GPIO_PP | BMI088_ACC_INT1_GPIO_LOW, BMI088_INT1_IO_CTRL_ERROR},
{BMI088_INT_MAP_DATA, BMI088_ACC_INT1_DRDY_INTERRUPT, BMI088_INT_MAP_DATA_ERROR}
};
static uint8_t write_BMI088_gyro_reg_data_error[BMI088_WRITE_GYRO_REG_NUM][3] =
{
{BMI088_GYRO_RANGE, BMI088_GYRO_2000, BMI088_GYRO_RANGE_ERROR},
{BMI088_GYRO_BANDWIDTH, BMI088_GYRO_2000_230_HZ | BMI088_GYRO_BANDWIDTH_MUST_Set, BMI088_GYRO_BANDWIDTH_ERROR},
{BMI088_GYRO_LPM1, BMI088_GYRO_NORMAL_MODE, BMI088_GYRO_LPM1_ERROR},
{BMI088_GYRO_CTRL, BMI088_DRDY_ON, BMI088_GYRO_CTRL_ERROR},
{BMI088_GYRO_INT3_INT4_IO_CONF, BMI088_GYRO_INT3_GPIO_PP | BMI088_GYRO_INT3_GPIO_LOW, BMI088_GYRO_INT3_INT4_IO_CONF_ERROR},
{BMI088_GYRO_INT3_INT4_IO_MAP, BMI088_GYRO_DRDY_IO_INT3, BMI088_GYRO_INT3_INT4_IO_MAP_ERROR}
{
{BMI088_GYRO_RANGE, BMI088_GYRO_2000, BMI088_GYRO_RANGE_ERROR},
{BMI088_GYRO_BANDWIDTH, BMI088_GYRO_2000_230_HZ | BMI088_GYRO_BANDWIDTH_MUST_Set, BMI088_GYRO_BANDWIDTH_ERROR},
{BMI088_GYRO_LPM1, BMI088_GYRO_NORMAL_MODE, BMI088_GYRO_LPM1_ERROR},
{BMI088_GYRO_CTRL, BMI088_DRDY_ON, BMI088_GYRO_CTRL_ERROR},
{BMI088_GYRO_INT3_INT4_IO_CONF, BMI088_GYRO_INT3_GPIO_PP | BMI088_GYRO_INT3_GPIO_LOW, BMI088_GYRO_INT3_INT4_IO_CONF_ERROR},
{BMI088_GYRO_INT3_INT4_IO_MAP, BMI088_GYRO_DRDY_IO_INT3, BMI088_GYRO_INT3_INT4_IO_MAP_ERROR}
};
static void Calibrate_MPU_Offset(IMU_Data_t *bmi088);
uint8_t BMI088_init(SPI_HandleTypeDef *bmi088_SPI, uint8_t calibrate)
{
BMI088_SPI = bmi088_SPI;
@ -128,11 +127,10 @@ uint8_t BMI088_init(SPI_HandleTypeDef *bmi088_SPI, uint8_t calibrate)
return error;
}
void Calibrate_MPU_Offset(IMU_Data_t *bmi088)
{
static float startTime;
static uint16_t CaliTimes = 6000;
static uint16_t CaliTimes = 6000;
uint8_t buf[8] = {0, 0, 0, 0, 0, 0};
int16_t bmi088_raw_temp;
float gyroMax[3], gyroMin[3];
@ -333,16 +331,16 @@ void BMI088_Read(IMU_Data_t *bmi088)
{
static uint8_t buf[8] = {0, 0, 0, 0, 0, 0};
static int16_t bmi088_raw_temp;
static float dt=1.0;
static uint8_t first_read_flag=0;
if(!first_read_flag)
static float dt = 1.0;
static uint8_t first_read_flag = 0;
if (!first_read_flag)
{
first_read_flag=1;
first_read_flag = 1;
DWT_GetDeltaT(&offset_cal_DWT_Count);
}
else
{
dt=DWT_GetDeltaT(&offset_cal_DWT_Count)*1000.0;
dt = DWT_GetDeltaT(&offset_cal_DWT_Count) * 1000.0;
}
BMI088_accel_read_muli_reg(BMI088_ACCEL_XOUT_L, buf, 6);
@ -359,11 +357,11 @@ void BMI088_Read(IMU_Data_t *bmi088)
if (caliOffset)
{
bmi088_raw_temp = (int16_t)((buf[3]) << 8) | buf[2];
bmi088->Gyro[0] = bmi088_raw_temp * BMI088_GYRO_SEN - bmi088->GyroOffset[0]*dt;
bmi088->Gyro[0] = bmi088_raw_temp * BMI088_GYRO_SEN - bmi088->GyroOffset[0] * dt;
bmi088_raw_temp = (int16_t)((buf[5]) << 8) | buf[4];
bmi088->Gyro[1] = bmi088_raw_temp * BMI088_GYRO_SEN - bmi088->GyroOffset[1]*dt;
bmi088->Gyro[1] = bmi088_raw_temp * BMI088_GYRO_SEN - bmi088->GyroOffset[1] * dt;
bmi088_raw_temp = (int16_t)((buf[7]) << 8) | buf[6];
bmi088->Gyro[2] = bmi088_raw_temp * BMI088_GYRO_SEN - bmi088->GyroOffset[2]*dt;
bmi088->Gyro[2] = bmi088_raw_temp * BMI088_GYRO_SEN - bmi088->GyroOffset[2] * dt;
}
else
{

View File

@ -2,6 +2,7 @@
******************************************************************************
* @file ins_task.c
* @author Wang Hongxi
* @author annotation and modificaiton by neozng
* @version V2.0.0
* @date 2022/2/23
* @brief
@ -37,6 +38,17 @@ attitude_t *GetINSptr()
return (attitude_t *)&INS.Roll;
}
/**
* @brief
*
*/
static void IMU_Temperature_Ctrl(void)
{
PID_Calculate(&TempCtrl, BMI088.Temperature, RefTemp);
imu_pwm_set(float_constrain(float_rounding(TempCtrl.Output), 0, UINT32_MAX));
}
void INS_Init(void)
{
// while (BMI088_init(&hspi1, 1) != BMI088_NO_ERROR);
@ -242,17 +254,6 @@ static void IMU_Param_Correction(IMU_Param_t *param, float gyro[3], float accel[
lastRollOffset = param->Roll;
}
/**
* @brief
*
*/
void IMU_Temperature_Ctrl(void)
{
PID_Calculate(&TempCtrl, BMI088.Temperature, RefTemp);
imu_pwm_set(float_constrain(float_rounding(TempCtrl.Output), 0, UINT32_MAX));
}
//------------------------------------functions below are not used in this demo-------------------------------------------------
//----------------------------------you can read them for learning or programming-----------------------------------------------
//----------------------------------they could also be helpful for further design-----------------------------------------------

View File

@ -92,12 +92,6 @@ void INS_Init(void);
*/
void INS_Task(void);
/**
* @brief
*
*/
void IMU_Temperature_Ctrl(void);
/**
* @brief ,dq/dt=0.5Ωq
*

3
modules/imu/ins_task.md Normal file
View File

@ -0,0 +1,3 @@
# ins_task
<p align='right'>neozng1@hnu.edu.cn</p>

View File

@ -0,0 +1 @@
# master_process

View File

@ -0,0 +1,64 @@
# 湖南大学RoboMaster电控组通信协议
可用于视觉,以及其他自研模块(仅限串口通信)
## 一、串口配置
通信方式是串口,配置为波特率 1152008 位数据位1 位停止位,无硬件流控,无校验位。
## 二、数据帧说明
以下所有低位在前发送,数据长度可变。
1. 通信协议格式
| 帧头 | 数据ID | 数据 | 帧尾 |
| ----------------------- | -------------- | ------------- | :---------------------------------- |
| protocol_header(4-byte) | cmd_id(2-byte) | data (n-byte) | frame_tail(2-byteCRC16整包校验) |
2. 帧头详细定义
| 帧头 | 偏移位置 | 字节大小 | 内容 |
| ----------- | -------- | -------- | ----------------------------- |
| sof(CMD) | 0 | 1 | 数据帧起始字节,固定值为 0xA5 |
| data_length | 1 | 2 | 数据帧中 data 的长度 |
| crc_check | 3 | 1 | 帧头CRC校验 |
3. cmd_id 命令码 ID 说明 **(字节偏移 4字节大小 2)**
| 命令码 | 数据段长度 | 功能说明 |
| -------------- | --------------- | -------- |
| 0x0001(可修改) | 2 byte (16-bit) | 视觉数据 |
| ....... | | |
4. 数据段data (n-byte)
| 数据 | 偏移位置 | 字节大小 | 内容 |
| -------------- | -------- | --------------- | ------------------------------------- |
| flags_register | 6 | 2 | 16位标志置位寄存器 |
| float_data | 8 | 4 * data_length | float数据内容4 * data_length-byte |
5. frame_tail(CRC16整包校验)
## 三、协议接口说明
```c
/*更新发送数据帧,并计算发送数据帧长度*/
void get_protocol_send_data(uint16_t send_id, //信号id
uint16_t flags_register, // 16位寄存器
float *tx_data, //待发送的float数据
uint8_t float_length, // float的数据长度
uint8_t *tx_buf, //待发送的数据帧
uint16_t *tx_buf_len); //待发送的数据帧长度
```
将float_data字段准备好放入`tx_data[]`并设置好标志位`flags_register`之后,调用此函数。它将计算循环冗余校验码,并把数据转换成串口发送的格式,放在`tx_buf[]`中。
```c
/*接收数据处理*/
uint16_t get_protocol_info(uint8_t *rx_buf, //接收到的原始数据
uint16_t *flags_register, //接收数据的16位寄存器地址
float *rx_data); //接收的float数据存储地址
```
将收到的一包原始数据buff地址传入若校验通过会把收到的标志位和float数据解析出来保存在`flags_register*`和 `rx_data[]`中。

View File

@ -1,5 +1,6 @@
#include "motor_task.h"
void MotorControlTask()
{
DJIMotorControl();

View File

@ -15,6 +15,12 @@
#include "HT04.h"
#include "dji_motor.h"
// 舵机控制任务的频率设定为20Hz或更低
// 开关式的舵机控制不应该放在该函数中
/**
* @brief
*
*/
void MotorControlTask();
#endif // !MOTOR_TASK_H