Compare commits

...

5 Commits

36 changed files with 7409 additions and 5193 deletions

47
.vscode/settings.json vendored
View File

@ -1,6 +1,51 @@
{
"files.associations": {
"service_error_count.h": "c",
"ptz_header_file.h": "c"
"ptz_header_file.h": "c",
"systick.h": "c",
"rotate_bldc.h": "c",
"service_areascan.h": "c",
"device_adc_collect.h": "c",
"includes.h": "c",
"gd32f4xx.h": "c",
"service_statusmonitor.h": "c",
"ptz_type_select.h": "c",
"ptz_struct.h": "c",
"tmp75.h": "c",
"ptz_default_value.h": "c",
"service_selfcheck.h": "c",
"gd32f4xx_gpio.h": "c",
"service_presetbitscan.h": "c",
"rotate_step.h": "c",
"rotate_servo.h": "c",
"speed_to_step.h": "c",
"timer.h": "c",
"tmc2160.h": "c",
"bsp_os.h": "c",
"ptz_global_variable.h": "c",
"gd32f4xx_adc.h": "c",
"mb85rc64.h": "c",
"drv_i2c.h": "c",
"delay.h": "c",
"as5047d.h": "c",
"rotate_electricstable.h": "c",
"drv_adc.h": "c",
"service_update.h": "c",
"speed_to_servomotor.h": "c",
"service_autoreturn.h": "c",
"angle_zerooffset.h": "c",
"full_bridge.h": "c",
"l6235d.h": "c",
"device_wdog.h": "c",
"agent_hyt.h": "c",
"device_heatresistor.h": "c",
"rotate_plan.h": "c",
"sock_utils.h": "c",
"device_photoelectricswitch.h": "c",
"angle_poweroffsave.h": "c",
"comm_cfginfo.h": "c",
"servomotor.h": "c",
"pdebug.h": "c",
"limits": "c"
}
}

File diff suppressed because it is too large Load Diff

View File

@ -19,7 +19,6 @@
#include "enet_to_udp.h"
#include "pdebug.h"
#include "Lan8720.h"
#include "device_adc_collect.h"
#include "service_areascan.h"
#include "service_presetbitscan.h"
#include "service_selfcheck.h"
@ -44,7 +43,8 @@
#include "ptz_global_variable.h"
#include "beep.h"
#include "rotate_step.h"
#include "speed_to_step.h"
// #include "speed_to_step.h"
#include "speed_to_servoMotor.h"
#include "full_bridge.h"
#include "Timer.h"
#include "systick.h"
@ -207,15 +207,15 @@ static void task_start (void *p_arg)
beep_disable();
while (DEF_TRUE) {
while (DEF_TRUE) {
OSTimeDlyHMSM(0u, 0u, 1u, 0u);
OSTaskDel(OS_PRIO_SELF);
}
}
/// 主函数
/// 主函数
///
/// 创建第一个任务,由该任务再创建其他功能任务
/// 创建第一个任务,由该任务再创建其他功能任务
/// @param none
/// @param none
/// @return none
@ -240,7 +240,7 @@ int main (void)
(INT8U ) TASK_START_PRIO,
(INT16U ) TASK_START_PRIO,
(OS_STK *)&task_start_stk[0],
(INT32U ) TASK_START_STK_SIZE,
(INT32U ) TASK_START_STK_SIZE,
(void *) 0,
(INT16U )(OS_TASK_OPT_STK_CHK | OS_TASK_OPT_STK_CLR));

View File

@ -145,6 +145,16 @@
#define TASK_PTZ_TASK_PRINTF_STK_SIZE 200u
//解析水平电机返回的数据
#define TASK_RECV_HORI_SERVO_PRIO 56u
#define TASK_RECV_HORI_SERVO_STK_SIZE 200u
//解析俯仰电机返回的数据
#define TASK_RECV_VERT_SERVO_PRIO 57u
#define TASK_RECV_VERT_SERVO_STK_SIZE 200u
//#define ????????????????????_PRIO 55u
//#define ????????????????????_STK_SIZE 150u
/*******************************************************************************/

View File

@ -10,18 +10,19 @@ static float power_v1;//
PowerOffData power_off_data;
//电压采集
static float ptz_voltage_adc1()
{
unsigned short int adc1_value;
float float_adc1;
// //电压采集
// static float ptz_voltage_adc1()
// {
// unsigned short int adc1_value;
// float float_adc1;
adc_software_trigger_enable(ADC1,ADC_INSERTED_CHANNEL);
adc1_value = ADC_IDATA1(ADC1);
// adc_software_trigger_enable(ADC1,ADC_INSERTED_CHANNEL);
// adc1_value = ADC_IDATA1(ADC1);
float_adc1 = (float)adc1_value / 4096.0 * 36.3;
return float_adc1;
}
// float_adc1 = (float)adc1_value / 4096.0 * 12.55 *3.38;
// // float_adc1 = (float)adc1_value / 4096.0 * 36.3;
// return float_adc1;
// }
static float ptz_power_off_data_crc(PowerOffData data)
{
@ -89,10 +90,12 @@ char ptz_power_off_data_save(unsigned short int add)
for(i = 0; i < PTZ_POWER_OFF_DATA_SAVE_NUM; i++)
{
memset(&power_off_data_b, 0, sizeof(power_off_data_b));
mb85rc64_page_write(add, (unsigned char *)&power_off_data, sizeof(power_off_data));
// mb85rc64_page_write(add, (unsigned char *)&power_off_data, sizeof(power_off_data));
mb85rc64_write_read(add, (unsigned char *)&power_off_data, sizeof(power_off_data), PAGE_WRITE);
asm("nop");
asm("nop");
mb85rc64_add_read(add, (unsigned char *)&power_off_data_b, sizeof(power_off_data_b));
// mb85rc64_add_read(add, (unsigned char *)&power_off_data_b, sizeof(power_off_data_b));
mb85rc64_write_read(add, (unsigned char *)&power_off_data_b, sizeof(power_off_data_b), ADDR_READ);
if(memcmp(&power_off_data_b, &power_off_data, sizeof(power_off_data)) == 0)//判断擦除数据是否正确
{
BSP_OS_SemPost(&ptz_power_off_mutex);
@ -117,7 +120,8 @@ char ptz_power_off_data_read()
for(i = 0; i < PTZ_POWER_OFF_DATA_READ_NUM; i++)
{
memset(&power_off_data_a, 0, sizeof(power_off_data_a));
mb85rc64_add_read(PTZ_MB85RC64_ADD_A, (unsigned char *)&power_off_data_a, sizeof(power_off_data_a));
// mb85rc64_add_read(PTZ_MB85RC64_ADD_A, (unsigned char *)&power_off_data_a, sizeof(power_off_data_a));
mb85rc64_write_read(PTZ_MB85RC64_ADD_A, (unsigned char *)&power_off_data_a, sizeof(power_off_data_a), ADDR_READ);
if(power_off_data_a.crc == ptz_power_off_data_crc(power_off_data_a) && power_off_data_a.crc != 0)
{
data_a = 1;
@ -129,7 +133,8 @@ char ptz_power_off_data_read()
for(i = 0; i < PTZ_POWER_OFF_DATA_READ_NUM; i++)
{
memset(&power_off_data_b, 0, sizeof(power_off_data_b));
mb85rc64_add_read(PTZ_MB85RC64_ADD_B, (unsigned char *)&power_off_data_b, sizeof(power_off_data_b));
// mb85rc64_add_read(PTZ_MB85RC64_ADD_B, (unsigned char *)&power_off_data_b, sizeof(power_off_data_b));
mb85rc64_write_read(PTZ_MB85RC64_ADD_B, (unsigned char *)&power_off_data_b, sizeof(power_off_data_b), ADDR_READ);
if(power_off_data_b.crc == ptz_power_off_data_crc(power_off_data_b) && power_off_data_b.crc != 0)
{
data_b = 1;
@ -290,10 +295,12 @@ char ptz_power_off_data_erase(unsigned short int add)
for(i = 0; i < PTZ_POWER_OFF_DATA_SAVE_NUM; i++)
{
memset(&power_off_data_a, 0, sizeof(power_off_data_a));
mb85rc64_page_write(add, (unsigned char *)&power_off_data, sizeof(power_off_data));
// mb85rc64_page_write(add, (unsigned char *)&power_off_data, sizeof(power_off_data));
mb85rc64_write_read(add, (unsigned char *)&power_off_data, sizeof(power_off_data), PAGE_WRITE);
asm("nop");
asm("nop");
mb85rc64_add_read(add, (unsigned char *)&power_off_data_a, sizeof(power_off_data_a));
// mb85rc64_add_read(add, (unsigned char *)&power_off_data_a, sizeof(power_off_data_a));
mb85rc64_write_read(add, (unsigned char *)&power_off_data_a, sizeof(power_off_data_a), ADDR_READ);
if(memcmp(&power_off_data_a, &power_off_data, sizeof(power_off_data)) == 0)//判断擦除数据是否正确
{
BSP_OS_SemPost(&ptz_power_off_mutex);
@ -363,7 +370,7 @@ static char ptz_power_off_task()
OSTimeDlyHMSM(0u, 0u, 0u, 2u);
//读取实时电压
g_ptz.Voltage = ptz_voltage_adc1();
g_ptz.Voltage = ptz_Voltage_collect_adc1_task();
//判断读出的电压是否大于0以及是否是一个数字
if(g_ptz.Voltage < 0 || isnan(g_ptz.Voltage) == 1)
{
@ -374,9 +381,9 @@ static char ptz_power_off_task()
{
//OSTimeDlyHMSM(0u, 0u, 0u, 1u);
asm("nop");asm("nop");asm("nop");asm("nop");asm("nop");
g_ptz.Voltage = ptz_voltage_adc1();//再采集一次
g_ptz.Voltage = ptz_Voltage_collect_adc1_task();//再采集一次
asm("nop");asm("nop");asm("nop");asm("nop");asm("nop");
g_ptz.Voltage = ptz_voltage_adc1();//再采集一次
g_ptz.Voltage = ptz_Voltage_collect_adc1_task();//再采集一次
//判断读出的电压是否小于于0以及是否是一个数字
if(g_ptz.Voltage < 0 || isnan(g_ptz.Voltage) == 1)
{
@ -385,8 +392,8 @@ static char ptz_power_off_task()
}
power_v = g_ptz.Voltage;
#endif
#endif
/*****************************************强制保存位置数据********************************************************/
if(g_ptz.no_self_check_force_save == 1)
{
@ -510,13 +517,13 @@ static char ptz_power_off_task()
static OS_STK task_power_off_stk[POWER_OFF_STK_SIZE];
static void creat_task_power_off(void)
{
CPU_INT08U task_err;
CPU_INT08U task_err;
CPU_INT08U name_err;
task_err = OSTaskCreateExt((void (*)(void *)) ptz_power_off_task,
(void *) 0,
(OS_STK *)&task_power_off_stk[POWER_OFF_STK_SIZE - 1],
(INT8U ) POWER_OFF_PRIO,
(INT8U ) POWER_OFF_PRIO,
(INT16U ) POWER_OFF_PRIO,
(OS_STK *)&task_power_off_stk[0],
(INT32U ) POWER_OFF_STK_SIZE,
@ -532,7 +539,7 @@ static void creat_task_power_off(void)
void init_power_off_module(void)
{
#ifdef PTZ_NO_SELF_CHECK
mb85rc64_gpio_init();
// mb85rc64_gpio_init();
BSP_OS_SemCreate(&ptz_power_off_mutex,1u,"ptz_power_off_mutex");//创建信号量

View File

@ -2,6 +2,7 @@
#define __PTZ_POWER_OFF_H_
//#include "gd32f4xx_gpio.h"
#include "ptz_struct.h"
#include "drv_adc.h"
//L6235D涡轮蜗杆重型云台
#ifdef PTZ_HEAVY_WORM_L6235D_AS5047D
#define PTZ_POWER_DOWN_INC 0.2 //电压降低的量(伏)

View File

@ -0,0 +1,103 @@
#include "speed_to_servoMotor.h"
#include "ptz_header_file.h"
#include "servoMotor.h"
#ifdef PTZ_SERVO_MOTOR
//电机数据解析任务互斥量
BSP_OS_SEM g_horiMotorMutex;
BSP_OS_SEM g_vertMotorMutex;
/*!
\brief
\param[in] none
\param[out] none
\retval none
*/
static void ptz_recv_hori_servo_task()
{
CPU_INT08U err;
while(1) {
OSSemPend(g_horiMotorMutex, 0, &err);
}
}
/*!
\brief
\param[in] none
\param[out] none
\retval none
*/
static void ptz_recv_vert_servo_task()
{
CPU_INT08U err;
while(1) {
OSSemPend(g_vertMotorMutex, 0, &err);
}
}
static OS_STK task_recv_hori_servo_stk[TASK_RECV_HORI_SERVO_STK_SIZE];
static OS_STK task_recv_vert_servo_stk[TASK_RECV_HORI_SERVO_STK_SIZE];
static void creat_task_servo_recv_task(void)
{
CPU_INT08U task_err;
CPU_INT08U name_err;
task_err = OSTaskCreateExt((void (*)(void *)) ptz_recv_hori_servo_task,
(void *) 0,
(OS_STK *)&task_recv_hori_servo_stk[TASK_RECV_HORI_SERVO_STK_SIZE - 1],
(INT8U ) TASK_RECV_HORI_SERVO_PRIO,
(INT16U ) TASK_RECV_HORI_SERVO_PRIO,
(OS_STK *)&task_recv_hori_servo_stk[0],
(INT32U ) TASK_RECV_HORI_SERVO_STK_SIZE,
(void *) 0,
(INT16U )(OS_TASK_OPT_STK_CHK | OS_TASK_OPT_STK_CLR));
#if (OS_TASK_NAME_EN > 0)
OSTaskNameSet(TASK_VERT_PID_PRIO, "ptz_recv_hori_servo_task", &name_err);
#endif
if ((task_err == OS_ERR_NONE) && (name_err == OS_ERR_NONE)) {
pdebug(DEBUG_LEVEL_INFO,"create ptz_recv_hori_servo_task success...\n\r");
} else {
pdebug(DEBUG_LEVEL_FATAL,"create ptz_recv_hori_servo_task failed...\n\r");
}
task_err = OSTaskCreateExt((void (*)(void *)) ptz_recv_vert_servo_task,
(void *) 0,
(OS_STK *)&task_recv_vert_servo_stk[TASK_RECV_HORI_SERVO_STK_SIZE - 1],
(INT8U ) TASK_RECV_VERT_SERVO_PRIO,
(INT16U ) TASK_RECV_VERT_SERVO_PRIO,
(OS_STK *)&task_recv_vert_servo_stk[0],
(INT32U ) task_recv_vert_servo_stk,
(void *) 0,
(INT16U )(OS_TASK_OPT_STK_CHK | OS_TASK_OPT_STK_CLR));
#if (OS_TASK_NAME_EN > 0)
OSTaskNameSet(TASK_VERT_PID_PRIO, "ptz_recv_vert_servo_task", &name_err);
#endif
if ((task_err == OS_ERR_NONE) && (name_err == OS_ERR_NONE)) {
pdebug(DEBUG_LEVEL_INFO,"create ptz_recv_vert_servo_task success...\n\r");
} else {
pdebug(DEBUG_LEVEL_FATAL,"create ptz_recv_vert_servo_task failed...\n\r");
}
}
void Init_ServoMotorRecv(void)
{
g_horiMotorMutex = OSSemCreate(1);
g_vertMotorMutex = OSSemCreate(1);
creat_task_servo_recv_task();
}
#endif

View File

@ -0,0 +1,15 @@
#ifndef __DEVICE_SPEED_SERVOMOTOR_H_
#define __DEVICE_SPEED_SERVOMOTOR_H_
#include "ptz_type_select.h"
#ifdef PTZ_SERVO_MOTOR
void Init_ServoMotorRecv(void);
#endif
#endif

View File

@ -1,9 +1,21 @@
#include "speed_to_servoMotor.h"
#include "ptz_header_file.h"
#include "servoMotor.h"
#ifdef PTZ_SERVO_MOTOR
//云台伺服电机通信信号量,增加发送的数据信号量+1发送完成信号量-1
BSP_OS_SEM g_horiSpeedSem;
BSP_OS_SEM g_vertSpeedSem;
//云台伺服电机能否发生数据互斥量
BSP_OS_SEM g_horiSpeedMutex;
BSP_OS_SEM g_vertSpeedMutex;
uint16_t memBuffer[linkListNodeLen * sendDataBufNumber * 2] = {0};
OS_MEM *g_memPtr;
ptzServoLinkList g_servoMotorLinkList = {0};
//发送云台实际转速
void ptz_send_speed(char dev, char speed)
@ -44,51 +56,195 @@ void ptz_send_speed(char dev, char speed)
}
}
/*!
\brief
\param[in] data
\param[out] none
\retval none
*/
void servoLinkListMemPut(linkList *data)
{
if (data == NULL) {
return;
}
linkList *ptr;
ptr = data;
data = data->next;
OSMemPut(g_memPtr, (uint8_t *)ptr);
}
static void ptz_hori_step_speed_task()
{
while(1)
{
if(g_ptz.hori_start_stop_set == PTZ_HORI_START)
{
/*!
\brief
\param[in] motor
horiMotor
vertMotor
\param[in] *data
\param[in] dataLen
\param[in] priority
\param[out] none
\retval none
*/
void servoSendData(uint8_t motor,uint8_t *data, uint8_t dataLen, uint8_t priority)
{
if ((motor != horiMotorType) && (motor!= vertMotorType)) {
return;
}
if (data == NULL) {
return;
}
if (dataLen > sendDataBufLen) {
return;
}
if ((priority != highPriority) && (priority != lowPriority)) {
return;
}
linkList *ptr = NULL;
CPU_INT08U err;
//保存数据到链表节点
ptr = OSMemGet(g_memPtr, &err);
ptr->length = dataLen;
memcpy(ptr->data, data, dataLen);
//将节点添加进入链表中
if (motor == horiMotorType) {
if (g_servoMotorLinkList.horiMotor.linkListNum > sendDataBufNumber) {
OSMemPut(g_memPtr, ptr);
return;
}
if (priority == highPriority) {
g_servoMotorLinkList.horiMotor.LinkListTail_H = ptr;
if (g_servoMotorLinkList.horiMotor.LinkListHead_H == NULL) {
g_servoMotorLinkList.horiMotor.LinkListHead_H
= g_servoMotorLinkList.horiMotor.LinkListTail_H;
}
}
else {
g_servoMotorLinkList.horiMotor.LinkListTail_L = ptr;
if (g_servoMotorLinkList.horiMotor.LinkListHead_L == NULL) {
g_servoMotorLinkList.horiMotor.LinkListHead_L
= g_servoMotorLinkList.horiMotor.LinkListTail_L;
}
}
//释放信号量,通知能发送一次
OSSemPost(g_horiSpeedSem);
}
else {
if (g_servoMotorLinkList.vertMotor.linkListNum > sendDataBufNumber) {
OSMemPut(g_memPtr, ptr);
return;
}
if (priority == highPriority) {
g_servoMotorLinkList.vertMotor.LinkListTail_H = ptr;
if (g_servoMotorLinkList.vertMotor.LinkListHead_H == NULL) {
g_servoMotorLinkList.vertMotor.LinkListHead_H
= g_servoMotorLinkList.vertMotor.LinkListTail_H;
}
}
else {
g_servoMotorLinkList.vertMotor.LinkListTail_L = ptr;
if (g_servoMotorLinkList.vertMotor.LinkListHead_L == NULL) {
g_servoMotorLinkList.vertMotor.LinkListHead_L
= g_servoMotorLinkList.vertMotor.LinkListTail_L;
}
}
//释放信号量,通知能发送一次
OSSemPost(g_vertSpeedSem);
}
}
static void ptz_hori_servo_task()
{
CPU_INT08U err;
while(1) {
// if(g_ptz.hori_start_stop_set == PTZ_HORI_START)
// {
// }
// if(g_ptz.hori_start_stop_set == PTZ_HORI_STOP)
// {
// }
OSSemPend(g_horiSpeedMutex, 0, &err);
OSSemPend(g_horiSpeedSem, 0, &err);
// 高优先级链表中数据先发送
if (g_servoMotorLinkList.horiMotor.LinkListHead_H != NULL) {
//发送数据
g_servoMotorLinkList.horiMotor.linkListNum = highPriority;
continue;
}
if(g_ptz.hori_start_stop_set == PTZ_HORI_STOP)
{
// 高优先级链表中无数据时,发送低优先级中的数据
if (g_servoMotorLinkList.horiMotor.LinkListHead_L != NULL) {
//发送数据
g_servoMotorLinkList.horiMotor.linkListNum = lowPriority;
}
else {
pdebug(DEBUG_LEVEL_FATAL,"ptz_hori_servo_task no data...\n\r");
}
OSTimeDlyHMSM(0u, 0u, 0u, 10);
}
}
static void ptz_vert_step_speed_task()
static void ptz_vert_servo_task()
{
while(1)
{
if(g_ptz.vert_start_stop_set == PTZ_VERT_START)
{
CPU_INT08U err;
while(1) {
// if(g_ptz.vert_start_stop_set == PTZ_VERT_START)
// {
// }
// if(g_ptz.vert_start_stop_set == PTZ_VERT_STOP)
// {
// }
OSSemPend(g_vertSpeedMutex, 0, &err);
OSSemPend(g_vertSpeedSem, 0, &err);
// 高优先级链表中数据先发送
if (g_servoMotorLinkList.vertMotor.LinkListHead_H != NULL) {
g_servoMotorLinkList.vertMotor.linkListNum = highPriority;
continue;
}
// 高优先级链表中无数据时,发送低优先级中的数据
if (g_servoMotorLinkList.vertMotor.LinkListHead_L != NULL) {
g_servoMotorLinkList.vertMotor.linkListNum = highPriority;
}
else {
pdebug(DEBUG_LEVEL_FATAL,"ptz_vert_servo_task no data...\n\r");
}
if(g_ptz.vert_start_stop_set == PTZ_VERT_STOP)
{
}
OSTimeDlyHMSM(0u, 0u, 0u, 10);
}
}
static OS_STK task_hori_step_speed_stk[TASK_HORI_PID_STK_SIZE];
static void creat_task_hori_step_speed_task(void)
static OS_STK task_hori_servo_stk[TASK_HORI_PID_STK_SIZE];
static void creat_task_hori_servo_task(void)
{
CPU_INT08U task_err;
CPU_INT08U name_err;
task_err = OSTaskCreateExt((void (*)(void *)) ptz_hori_step_speed_task,
task_err = OSTaskCreateExt((void (*)(void *)) ptz_hori_servo_task,
(void *) 0,
(OS_STK *)&task_hori_step_speed_stk[TASK_HORI_PID_STK_SIZE - 1],
(OS_STK *)&task_hori_servo_stk[TASK_HORI_PID_STK_SIZE - 1],
(INT8U ) TASK_HORI_PID_PRIO,
(INT16U ) TASK_HORI_PID_PRIO,
(OS_STK *)&task_hori_step_speed_stk[0],
(OS_STK *)&task_hori_servo_stk[0],
(INT32U ) TASK_HORI_PID_STK_SIZE,
(void *) 0,
(INT16U )(OS_TASK_OPT_STK_CHK | OS_TASK_OPT_STK_CLR));
@ -104,46 +260,75 @@ static void creat_task_hori_step_speed_task(void)
}
static OS_STK task_vert_step_speed_stk[TASK_VERT_PID_STK_SIZE];
static void creat_task_vert_step_speed_task(void)
static OS_STK task_vert_servo_stk[TASK_VERT_PID_STK_SIZE];
static void creat_task_vert_servo_task(void)
{
CPU_INT08U task_err;
CPU_INT08U name_err;
task_err = OSTaskCreateExt((void (*)(void *)) ptz_vert_step_speed_task,
task_err = OSTaskCreateExt((void (*)(void *)) ptz_vert_servo_task,
(void *) 0,
(OS_STK *)&task_vert_step_speed_stk[TASK_VERT_PID_STK_SIZE - 1],
(OS_STK *)&task_vert_servo_stk[TASK_VERT_PID_STK_SIZE - 1],
(INT8U ) TASK_VERT_PID_PRIO,
(INT16U ) TASK_VERT_PID_PRIO,
(OS_STK *)&task_vert_step_speed_stk[0],
(OS_STK *)&task_vert_servo_stk[0],
(INT32U ) TASK_VERT_PID_STK_SIZE,
(void *) 0,
(INT16U )(OS_TASK_OPT_STK_CHK | OS_TASK_OPT_STK_CLR));
(INT16U )(OS_TASK_OPT_STK_CHK | OS_TASK_OPT_STK_CLR));
#if (OS_TASK_NAME_EN > 0)
OSTaskNameSet(TASK_VERT_PID_PRIO, "ptz_vert_step_speed_task", &name_err);
OSTaskNameSet(TASK_VERT_PID_PRIO, "ptz_vert_servo_task", &name_err);
#endif
if ((task_err == OS_ERR_NONE) && (name_err == OS_ERR_NONE)) {
pdebug(DEBUG_LEVEL_INFO,"create ptz_vert_step_speed_task success...\n\r");
pdebug(DEBUG_LEVEL_INFO,"create ptz_vert_servo_task success...\n\r");
} else {
pdebug(DEBUG_LEVEL_FATAL,"create ptz_vert_step_speed_task failed...\n\r");
pdebug(DEBUG_LEVEL_FATAL,"create ptz_vert_servo_task failed...\n\r");
}
}
void init_speed_module(void)
{
g_horiSpeedSem = OSSemCreate(0);
g_vertSpeedSem = OSSemCreate(0);
g_horiSpeedMutex = OSSemCreate(1);
g_vertSpeedMutex = OSSemCreate(1);
OSSemPost(g_horiSpeedMutex);
OSSemPost(g_vertSpeedMutex);
CPU_INT08U err;
g_memPtr = OSMemCreate(memBuffer, sendDataBufNumber * 2, linkListNodeLen, &err);
if (err != OS_ERR_NONE) {
pdebug(DEBUG_LEVEL_FATAL, "Failed to create the motor memory pool\n\r");
}
//初始化链表头尾
g_servoMotorLinkList.horiMotor.LinkListHead_H = NULL;
g_servoMotorLinkList.horiMotor.LinkListHead_L = NULL;
g_servoMotorLinkList.horiMotor.LinkListTail_H = NULL;
g_servoMotorLinkList.horiMotor.LinkListTail_L = NULL;
g_servoMotorLinkList.horiMotor.linkListPriority = nonePriority;
g_servoMotorLinkList.horiMotor.linkListNum = 0;
g_servoMotorLinkList.vertMotor.LinkListHead_H = NULL;
g_servoMotorLinkList.vertMotor.LinkListHead_L = NULL;
g_servoMotorLinkList.vertMotor.LinkListTail_H = NULL;
g_servoMotorLinkList.vertMotor.LinkListTail_L = NULL;
g_servoMotorLinkList.vertMotor.linkListPriority = nonePriority;
g_servoMotorLinkList.vertMotor.linkListNum = 0;
servoMotorInit();
creat_task_hori_step_speed_task();
creat_task_vert_step_speed_task();
Init_ServoMotorRecv();
creat_task_hori_servo_task();
creat_task_vert_servo_task();
}
#endif

View File

@ -1,13 +1,75 @@
#ifndef __DEVICE_SPEED_SERVOMOTOR_H_
#define __DEVICE_SPEED_SERVOMOTOR_H_
#include "ptz_type_select.h"
#include "stdint.h"
#include "ptz_header_file.h"
#include "servoMotor.h"
#include "servoMotor_recv.h"
#ifdef PTZ_SERVO_MOTOR
enum {
nonePriority = 0,
highPriority,
lowPriority,
};
enum {
horiMotorType = 0,
vertMotorType,
};
//发送数据缓冲区的个数
#define sendDataBufNumber 8
//发送数据缓冲区的长度
#define sendDataBufLen 25
//发送链表,当个节点最大大小
#define linkListNodeLen 50
//发送链表
typedef struct _linkList {
//发送的数据
uint8_t data[sendDataBufLen];
//发送的数据长度
uint16_t length;
//下一个节点
struct _linkList *next;
} linkList;
typedef struct _motorLinkList{
//发送数据,高优先级链表头
linkList *LinkListHead_H;
//发送数据,低优先级链表头
linkList *LinkListHead_L;
//水平电机发送数据,高优先级链表尾
linkList *LinkListTail_H;
//水平电机发送数据,低优先级链表尾
linkList *LinkListTail_L;
//当前发送数据的链表优先级
uint8_t linkListPriority;
//放入的数据个数
uint8_t linkListNum;
} motorLinkList;
typedef struct _ptzServoLinkList {
motorLinkList horiMotor;
motorLinkList vertMotor;
} ptzServoLinkList;
extern BSP_OS_SEM g_horiSpeedSem;
extern BSP_OS_SEM g_vertSpeedSem;
extern BSP_OS_SEM g_horiSpeedMutex;
extern BSP_OS_SEM g_vertSpeedMutex;
extern ptzServoLinkList g_servoMotorLinkList;
void ptz_send_speed(char dev, char speed);
void init_speed_module(void);
void init_speed_module(void);
void servoLinkListMemPut(linkList *data);
void servoSendData(uint8_t motor,uint8_t *data, uint8_t dataLen, uint8_t priority);
#endif
#endif

View File

@ -1,18 +1,8 @@
#include "device_adc_collect.h"
#include <includes.h>
#include "gd32f4xx.h"
#include "comm_types.h"
#include "ptz_struct.h"
#include "tmp75.h"
#include "w25q128.h"
#include "agent_hyt.h"
#include "ptz_type_select.h"
#include "pdebug.h"
#include "rotate_plan.h"
#include "rotate_bldc.h"
ADC_Phase_current H_ADC_Collect;
ADC_Phase_current V_ADC_Collect;
// ADC_Phase_current H_ADC_Collect;
// ADC_Phase_current V_ADC_Collect;
//发送云台工作电压
void ptz_send_voltage(char dev)
@ -44,150 +34,149 @@ void ptz_send_current(char dev)
ptz_send_data(dev, IData, sizeof(IData));
}
//发送云台温度
void ptz_send_temperature(char dev)
{
unsigned short int tem = 0;
unsigned char TData[7]= {0xff,0x00,0x00,0x00,0x00,0x00,0x00};
tem = (unsigned short int)(g_ptz.temperature * 100 + 0.5);
TData[1] = g_ptz.address;
TData[2] = 0xd6;
TData[3] = (unsigned char)(tem >> 8);
TData[4] = (unsigned char)(tem & 0x00ff);
TData[6] = MotorCalPelcoDSUM(TData,sizeof(TData));
// //发送云台温度
// void ptz_send_temperature(char dev)
// {
// unsigned short int tem = 0;
// unsigned char TData[7]= {0xff,0x00,0x00,0x00,0x00,0x00,0x00};
// tem = (unsigned short int)(g_ptz.temperature * 100 + 0.5);
// TData[1] = g_ptz.address;
// TData[2] = 0xd6;
// TData[3] = (unsigned char)(tem >> 8);
// TData[4] = (unsigned char)(tem & 0x00ff);
// TData[6] = MotorCalPelcoDSUM(TData,sizeof(TData));
ptz_send_data(dev,TData,sizeof(TData));
// ptz_send_data(dev,TData,sizeof(TData));
}
// }
//发送全桥驱动电路温度
void ptz_send_bridge_temperature(char dev)
{
unsigned short int tem = 0;
unsigned char TData[7]= {0xff,0x00,0x00,0x00,0x00,0x00,0x00};
//发送水平驱动侧
tem = (unsigned short int)(g_ptz.H_boad_temp * 100 + 0.5);
TData[1] = g_ptz.address;
TData[2] = 0xd7;
TData[3] = PTZ_HORI;
TData[4] = (unsigned char)(tem >> 8);
TData[5] = (unsigned char)(tem & 0x00ff);
TData[6] = MotorCalPelcoDSUM(TData,sizeof(TData));
// //发送全桥驱动电路温度
// void ptz_send_bridge_temperature(char dev)
// {
// unsigned short int tem = 0;
// unsigned char TData[7]= {0xff,0x00,0x00,0x00,0x00,0x00,0x00};
// //发送水平驱动侧
// tem = (unsigned short int)(g_ptz.H_boad_temp * 100 + 0.5);
// TData[1] = g_ptz.address;
// TData[2] = 0xd7;
// TData[3] = PTZ_HORI;
// TData[4] = (unsigned char)(tem >> 8);
// TData[5] = (unsigned char)(tem & 0x00ff);
// TData[6] = MotorCalPelcoDSUM(TData,sizeof(TData));
ptz_send_data(dev,TData,sizeof(TData));
// ptz_send_data(dev,TData,sizeof(TData));
OSTimeDlyHMSM(0u, 0u, 0u, 5u);
// OSTimeDlyHMSM(0u, 0u, 0u, 5u);
//发送垂直驱动侧
tem = (unsigned short int)(g_ptz.V_boad_temp * 100 + 0.5);
TData[1] = g_ptz.address;
TData[2] = 0xd7;
TData[3] = PTZ_VERT;
TData[4] = (unsigned char)(tem >> 8);
TData[5] = (unsigned char)(tem & 0x00ff);
TData[6] = MotorCalPelcoDSUM(TData,sizeof(TData));
// //发送垂直驱动侧
// tem = (unsigned short int)(g_ptz.V_boad_temp * 100 + 0.5);
// TData[1] = g_ptz.address;
// TData[2] = 0xd7;
// TData[3] = PTZ_VERT;
// TData[4] = (unsigned char)(tem >> 8);
// TData[5] = (unsigned char)(tem & 0x00ff);
// TData[6] = MotorCalPelcoDSUM(TData,sizeof(TData));
ptz_send_data(dev,TData,sizeof(TData));
}
// ptz_send_data(dev,TData,sizeof(TData));
// }
static float current_caculate(uint16_t I)
{
float i;
i = ((float)I/4096.0*3.3)/0.5;
return i;
}
// static float current_caculate(uint16_t I)
// {
// float i;
// i = ((float)I/4096.0*3.3)/0.5;
// return i;
// }
/*!
\brief ADC2初始化,
\param[in] none
\param[out] none
\retval none
\note LH @2022.07.21
*/
static void ADC2_Init()
{
/* 水平电机相电流PC0-UPA0-VPA3-W ---ADC2*/
//配置引脚时钟
rcu_periph_clock_enable(RCU_GPIOA);
rcu_periph_clock_enable(RCU_GPIOC);
gpio_mode_set(GPIOC,GPIO_MODE_ANALOG,GPIO_PUPD_NONE,GPIO_PIN_0);
gpio_mode_set(GPIOA,GPIO_MODE_ANALOG,GPIO_PUPD_NONE,GPIO_PIN_0);
gpio_mode_set(GPIOA,GPIO_MODE_ANALOG,GPIO_PUPD_NONE,GPIO_PIN_3);
// /*!
// \brief ADC2初始化,水平电机相电流采集
// \param[in] none
// \param[out] none
// \retval none
// \note LH @2022.07.21
// */
// static void ADC2_Init()
// {
// /* 水平电机相电流PC0-UPA0-VPA3-W ---ADC2*/
// //配置引脚时钟
// rcu_periph_clock_enable(RCU_GPIOA);
// rcu_periph_clock_enable(RCU_GPIOC);
// gpio_mode_set(GPIOC,GPIO_MODE_ANALOG,GPIO_PUPD_NONE,GPIO_PIN_0);
// gpio_mode_set(GPIOA,GPIO_MODE_ANALOG,GPIO_PUPD_NONE,GPIO_PIN_0);
// gpio_mode_set(GPIOA,GPIO_MODE_ANALOG,GPIO_PUPD_NONE,GPIO_PIN_3);
rcu_periph_clock_enable(RCU_ADC2);
//总线时钟20分频=6MHZ
adc_clock_config(ADC_ADCCK_PCLK2_DIV4);
/***********************************************/
// rcu_periph_clock_enable(RCU_ADC2);
// //总线时钟20分频=6MHZ
// adc_clock_config(ADC_ADCCK_PCLK2_DIV4);
// /***********************************************/
//对齐方式 ADC_INSERTED_CHANNEL
adc_data_alignment_config(ADC2,ADC_DATAALIGN_RIGHT);
//扫描模式
adc_special_function_config(ADC2,ADC_SCAN_MODE,ENABLE);
//外部触发关闭
adc_external_trigger_config(ADC2,ADC_INSERTED_CHANNEL,DISABLE);
//采集通道数
adc_channel_length_config(ADC2,ADC_INSERTED_CHANNEL,3);
// //对齐方式 ADC_INSERTED_CHANNEL
// adc_data_alignment_config(ADC2,ADC_DATAALIGN_RIGHT);
// //扫描模式
// adc_special_function_config(ADC2,ADC_SCAN_MODE,ENABLE);
// //外部触发关闭
// adc_external_trigger_config(ADC2,ADC_INSERTED_CHANNEL,DISABLE);
// //采集通道数
// adc_channel_length_config(ADC2,ADC_INSERTED_CHANNEL,3);
//通道注入顺序
adc_inserted_channel_config(ADC2,0,ADC_CHANNEL_10,ADC_SAMPLETIME_480);//u
adc_inserted_channel_config(ADC2,1,ADC_CHANNEL_0,ADC_SAMPLETIME_480);//v
adc_inserted_channel_config(ADC2,2,ADC_CHANNEL_3,ADC_SAMPLETIME_480);//w
// //通道注入顺序
// adc_inserted_channel_config(ADC2,0,ADC_CHANNEL_10,ADC_SAMPLETIME_480);//u
// adc_inserted_channel_config(ADC2,1,ADC_CHANNEL_0,ADC_SAMPLETIME_480);//v
// adc_inserted_channel_config(ADC2,2,ADC_CHANNEL_3,ADC_SAMPLETIME_480);//w
adc_enable(ADC2);
// adc_enable(ADC2);
adc_calibration_enable(ADC2);
}
// adc_calibration_enable(ADC2);
// }
/*!
\brief ADC0初始化,
\param[in] none
\param[out] none
\retval none
\note LH @2022.07.21
*/
static void ADC0_Init()
{
/* 垂直电机相电流PA4-UPA5-VPA6-W ---ADC0*/
//配置引脚时钟
rcu_periph_clock_enable(RCU_GPIOA);
gpio_mode_set(GPIOA,GPIO_MODE_ANALOG,GPIO_PUPD_NONE,GPIO_PIN_4);
gpio_mode_set(GPIOA,GPIO_MODE_ANALOG,GPIO_PUPD_NONE,GPIO_PIN_5);
gpio_mode_set(GPIOA,GPIO_MODE_ANALOG,GPIO_PUPD_NONE,GPIO_PIN_6);
// /*!
// \brief ADC0初始化,垂直电机相电流采集
// \param[in] none
// \param[out] none
// \retval none
// \note LH @2022.07.21
// */
// static void ADC0_Init()
// {
// /* 垂直电机相电流PA4-UPA5-VPA6-W ---ADC0*/
// //配置引脚时钟
// rcu_periph_clock_enable(RCU_GPIOA);
// gpio_mode_set(GPIOA,GPIO_MODE_ANALOG,GPIO_PUPD_NONE,GPIO_PIN_4);
// gpio_mode_set(GPIOA,GPIO_MODE_ANALOG,GPIO_PUPD_NONE,GPIO_PIN_5);
// gpio_mode_set(GPIOA,GPIO_MODE_ANALOG,GPIO_PUPD_NONE,GPIO_PIN_6);
rcu_periph_clock_enable(RCU_ADC0);
//总线时钟20分频=6MHZ
adc_clock_config(ADC_ADCCK_PCLK2_DIV4);
/***********************************************/
// rcu_periph_clock_enable(RCU_ADC0);
// //总线时钟20分频=6MHZ
// adc_clock_config(ADC_ADCCK_PCLK2_DIV4);
// /***********************************************/
//对齐方式 ADC_INSERTED_CHANNEL
adc_data_alignment_config(ADC0,ADC_DATAALIGN_RIGHT);
//扫描模式
adc_special_function_config(ADC0,ADC_SCAN_MODE,ENABLE);
//外部触发关闭
adc_external_trigger_config(ADC0,ADC_INSERTED_CHANNEL,DISABLE);
//采集通道数
adc_channel_length_config(ADC0,ADC_INSERTED_CHANNEL,3);
// //对齐方式 ADC_INSERTED_CHANNEL
// adc_data_alignment_config(ADC0,ADC_DATAALIGN_RIGHT);
// //扫描模式
// adc_special_function_config(ADC0,ADC_SCAN_MODE,ENABLE);
// //外部触发关闭
// adc_external_trigger_config(ADC0,ADC_INSERTED_CHANNEL,DISABLE);
// //采集通道数
// adc_channel_length_config(ADC0,ADC_INSERTED_CHANNEL,3);
//通道注入顺序
adc_inserted_channel_config(ADC0,0,ADC_CHANNEL_4,ADC_SAMPLETIME_480);//u
adc_inserted_channel_config(ADC0,1,ADC_CHANNEL_5,ADC_SAMPLETIME_480);//v
adc_inserted_channel_config(ADC0,2,ADC_CHANNEL_6,ADC_SAMPLETIME_480);//w
// //通道注入顺序
// adc_inserted_channel_config(ADC0,0,ADC_CHANNEL_4,ADC_SAMPLETIME_480);//u
// adc_inserted_channel_config(ADC0,1,ADC_CHANNEL_5,ADC_SAMPLETIME_480);//v
// adc_inserted_channel_config(ADC0,2,ADC_CHANNEL_6,ADC_SAMPLETIME_480);//w
adc_enable(ADC0);
// adc_enable(ADC0);
adc_calibration_enable(ADC0);
}
// adc_calibration_enable(ADC0);
// }
/* H_NTC-PB0 ,V_NTC-PB1 ----ADC1*/
@ -198,298 +187,299 @@ static void ADC0_Init()
\retval none
\note LH @2022.07.21
*/
static void ADC1_Init()
{
//配置引脚时钟
rcu_periph_clock_enable(RCU_GPIOC);
rcu_periph_clock_enable(RCU_GPIOB);
//引脚复用PC2——电压ADC1-CH12PC3——电流ADC1-CH13
gpio_mode_set(GPIOC,GPIO_MODE_ANALOG,GPIO_PUPD_NONE,GPIO_PIN_2);
gpio_mode_set(GPIOC,GPIO_MODE_ANALOG,GPIO_PUPD_NONE,GPIO_PIN_3);
/* H_NTC-PB0 ,V_NTC-PB1 */
gpio_mode_set(GPIOB,GPIO_MODE_ANALOG,GPIO_PUPD_NONE,GPIO_PIN_0);
gpio_mode_set(GPIOB,GPIO_MODE_ANALOG,GPIO_PUPD_NONE,GPIO_PIN_1);
// static void ADC1_Init()
// {
// //配置引脚时钟
// rcu_periph_clock_enable(RCU_GPIOC);
// // rcu_periph_clock_enable(RCU_GPIOB);
// //引脚复用PC2——电压ADC1-CH12PC3——电流ADC1-CH13
// gpio_mode_set(GPIOC,GPIO_MODE_ANALOG,GPIO_PUPD_NONE,GPIO_PIN_2);
// gpio_mode_set(GPIOC,GPIO_MODE_ANALOG,GPIO_PUPD_NONE,GPIO_PIN_3);
// // /* H_NTC-PB0 ,V_NTC-PB1 */
// // gpio_mode_set(GPIOB,GPIO_MODE_ANALOG,GPIO_PUPD_NONE,GPIO_PIN_0);
// // gpio_mode_set(GPIOB,GPIO_MODE_ANALOG,GPIO_PUPD_NONE,GPIO_PIN_1);
rcu_periph_clock_enable(RCU_ADC1);
//总线时钟20分频=6MHZ
adc_clock_config(ADC_ADCCK_PCLK2_DIV4);
/***********************************************/
// rcu_periph_clock_enable(RCU_ADC1);
// //总线时钟20分频=6MHZ
// adc_clock_config(ADC_ADCCK_PCLK2_DIV4);
// /***********************************************/
//对齐方式 ADC_INSERTED_CHANNEL
adc_data_alignment_config(ADC1,ADC_DATAALIGN_RIGHT);
//扫描模式
adc_special_function_config(ADC1,ADC_SCAN_MODE,ENABLE);
//外部触发关闭
adc_external_trigger_config(ADC1,ADC_INSERTED_CHANNEL,DISABLE);
//采集通道数
adc_channel_length_config(ADC1,ADC_INSERTED_CHANNEL,4);
// //对齐方式 ADC_INSERTED_CHANNEL
// adc_data_alignment_config(ADC1,ADC_DATAALIGN_RIGHT);
// //扫描模式
// adc_special_function_config(ADC1,ADC_SCAN_MODE,ENABLE);
// //外部触发关闭
// adc_external_trigger_config(ADC1,ADC_INSERTED_CHANNEL,DISABLE);
// //采集通道数
// adc_channel_length_config(ADC1,ADC_INSERTED_CHANNEL,2);
//通道注入顺序
adc_inserted_channel_config(ADC1,0,ADC_CHANNEL_13,ADC_SAMPLETIME_480);//电流
adc_inserted_channel_config(ADC1,1,ADC_CHANNEL_12,ADC_SAMPLETIME_480);//电压
adc_inserted_channel_config(ADC1,2,ADC_CHANNEL_8,ADC_SAMPLETIME_480);//H_NTC-PB0
adc_inserted_channel_config(ADC1,3,ADC_CHANNEL_9,ADC_SAMPLETIME_480);//V_NTC-PB1
// //通道注入顺序
// adc_inserted_channel_config(ADC1,0,ADC_CHANNEL_13,ADC_SAMPLETIME_480);//电流
// adc_inserted_channel_config(ADC1,1,ADC_CHANNEL_12,ADC_SAMPLETIME_480);//电压
// // adc_inserted_channel_config(ADC1,2,ADC_CHANNEL_8,ADC_SAMPLETIME_480);//H_NTC-PB0
// // adc_inserted_channel_config(ADC1,3,ADC_CHANNEL_9,ADC_SAMPLETIME_480);//V_NTC-PB1
adc_enable(ADC1);
// adc_enable(ADC1);
adc_calibration_enable(ADC1);
}
// adc_calibration_enable(ADC1);
// }
/*!
\brief
\param[in] none
\param[out] none
\retval none
\note LH @2022.07.19
*/
void H_ADC2_Phase_current()
{
adc_software_trigger_enable(ADC2,ADC_INSERTED_CHANNEL);
asm ("nop");
asm ("nop");
H_ADC_Collect.Phase_curr_U = current_caculate(ADC_IDATA0(ADC2));//U
asm ("nop");
H_ADC_Collect.Phase_curr_V = current_caculate(ADC_IDATA1(ADC2));//V
asm ("nop");
H_ADC_Collect.Phase_curr_W = current_caculate(ADC_IDATA2(ADC2));//W
// /*!
// \brief 水平电机相电流采集
// \param[in] none
// \param[out] none
// \retval none
// \note LH @2022.07.19
// */
// void H_ADC2_Phase_current()
// {
// adc_software_trigger_enable(ADC2,ADC_INSERTED_CHANNEL);
// asm ("nop");
// asm ("nop");
// H_ADC_Collect.Phase_curr_U = current_caculate(ADC_IDATA0(ADC2));//U
// asm ("nop");
// H_ADC_Collect.Phase_curr_V = current_caculate(ADC_IDATA1(ADC2));//V
// asm ("nop");
// H_ADC_Collect.Phase_curr_W = current_caculate(ADC_IDATA2(ADC2));//W
}
// }
/*!
\brief
\param[in] none
\param[out] none
\retval none
\note LH @2022.07.19
*/
void V_ADC0_Phase_current()
{
// int Ia,Ib,Ic;
adc_software_trigger_enable(ADC0,ADC_INSERTED_CHANNEL);
asm ("nop");
asm ("nop");
// Ia = ADC_IDATA0(ADC0);//U
V_ADC_Collect.Phase_curr_U = current_caculate(ADC_IDATA0(ADC0));//U
asm ("nop");
// Ib = ADC_IDATA1(ADC0);//V
V_ADC_Collect.Phase_curr_V = current_caculate(ADC_IDATA1(ADC0));//V
asm ("nop");
// Ic = ADC_IDATA2(ADC0);//W
V_ADC_Collect.Phase_curr_W = current_caculate(ADC_IDATA2(ADC0));//W
// /*!
// \brief 垂直电机相电流采集
// \param[in] none
// \param[out] none
// \retval none
// \note LH @2022.07.19
// */
// void V_ADC0_Phase_current()
// {
// // int Ia,Ib,Ic;
// adc_software_trigger_enable(ADC0,ADC_INSERTED_CHANNEL);
// asm ("nop");
// asm ("nop");
// // Ia = ADC_IDATA0(ADC0);//U
// V_ADC_Collect.Phase_curr_U = current_caculate(ADC_IDATA0(ADC0));//U
// asm ("nop");
// // Ib = ADC_IDATA1(ADC0);//V
// V_ADC_Collect.Phase_curr_V = current_caculate(ADC_IDATA1(ADC0));//V
// asm ("nop");
// // Ic = ADC_IDATA2(ADC0);//W
// V_ADC_Collect.Phase_curr_W = current_caculate(ADC_IDATA2(ADC0));//W
}
// }
#define R_constant 10.0 //千欧姆——分压电阻值
// #define R_constant 10.0 //千欧姆——分压电阻值
#define R_25 10000.0//热敏电阻常温下的电阻值
// #define R_25 10000.0//热敏电阻常温下的电阻值
#define Ntc_B 3435.0//常量B
// #define Ntc_B 3435.0//常量B
#define Kelvin_temp 273.15+25//常温——开尔文温度
//NTC电流
static float Ntc_current(uint16_t data)
{
static float curr;
curr = ((float)data / 4096.0 * 3.3)/R_constant;
return curr;
// #define Kelvin_temp 273.15+25//常温——开尔文温度
// //NTC电流
// static float Ntc_current(uint16_t data)
// {
// static float curr;
// curr = ((float)data / 4096.0 * 3.3)/R_constant;
// return curr;
}
//NTC电压
static float Ntc_voltage(uint16_t data)
{
static float voltage;
voltage = 3.3 - ((float)data / 4096.0 * 3.3);
return voltage;
}
//NTC电阻
static float Ntc_resis(uint16_t data)
{
static float resis,curr,voltage;
curr = Ntc_current(data);
voltage = Ntc_voltage(data);
resis = voltage / curr * 1000.0;//因为电流值放大了1000倍
return resis;
}
// }
// //NTC电压
// static float Ntc_voltage(uint16_t data)
// {
// static float voltage;
// voltage = 3.3 - ((float)data / 4096.0 * 3.3);
// return voltage;
// }
// //NTC电阻
// static float Ntc_resis(uint16_t data)
// {
// static float resis,curr,voltage;
// curr = Ntc_current(data);
// voltage = Ntc_voltage(data);
// resis = voltage / curr * 1000.0;//因为电流值放大了1000倍
// return resis;
// }
//NTC温度计算,开尔文温度
static float Ntc_temp(uint16_t adc_data)
{
float R_ntc;//实际电阻
double temp,K,j,l,m;//实际温度
R_ntc = Ntc_resis(adc_data);
K = R_ntc/10000.0;
j = log(K);//log e为底数
l = j/3435.0;
m = 1.0 /298.15;
temp = 1/(l+m);
// temp = 1/(j / Ntc_B + 1/Kelvin_temp);
return (float)temp;
}
// //NTC温度计算,开尔文温度
// static float Ntc_temp(uint16_t adc_data)
// {
// float R_ntc;//实际电阻
// double temp,K,j,l,m;//实际温度
// R_ntc = Ntc_resis(adc_data);
// K = R_ntc/10000.0;
// j = log(K);//log e为底数
// l = j/3435.0;
// m = 1.0 /298.15;
// temp = 1/(l+m);
// // temp = 1/(j / Ntc_B + 1/Kelvin_temp);
// return (float)temp;
// }
/*!
\brief
\param[in] none
\param[out] none
\retval none
\note LH @2022.07.19
*/
static void Ntc_value()//ADC1
{
float H_temp_f,V_temp_f;//初始温度,开尔文温度
short int H_temp,V_temp;//矫正温度,摄氏温度
// /*!
// \brief 热敏电阻计算主板温度
// \param[in] none
// \param[out] none
// \retval none
// \note LH @2022.07.19
// */
// static void Ntc_value()//ADC1
// {
// float H_temp_f,V_temp_f;//初始温度,开尔文温度
// short int H_temp,V_temp;//矫正温度,摄氏温度
adc_software_trigger_enable(ADC1,ADC_INSERTED_CHANNEL);
asm ("nop");
asm ("nop");
H_temp_f = Ntc_temp(ADC_IDATA2(ADC1));
asm ("nop");
asm ("nop");
V_temp_f = Ntc_temp(ADC_IDATA3(ADC1));
// adc_software_trigger_enable(ADC1,ADC_INSERTED_CHANNEL);
// asm ("nop");
// asm ("nop");
// H_temp_f = Ntc_temp(ADC_IDATA2(ADC1));
// asm ("nop");
// asm ("nop");
// V_temp_f = Ntc_temp(ADC_IDATA3(ADC1));
H_temp = (short int)(H_temp_f - 273.15 + 0.5);
// H_temp = (short int)(H_temp_f - 273.15 + 0.5);
V_temp = (short int)(V_temp_f - 273.15 + 0.5);
// V_temp = (short int)(V_temp_f - 273.15 + 0.5);
g_ptz.H_boad_temp = (float)H_temp;//该温度参数需要增加回传与查询
// g_ptz.H_boad_temp = (float)H_temp;//该温度参数需要增加回传与查询
g_ptz.V_boad_temp = (float)V_temp;
// g_ptz.V_boad_temp = (float)V_temp;
}
// }
//电压采集
static void ptz_Voltage_collect_adc1_task()
{
static float adc1_v[5];
static unsigned char adc1_num;
int j,k;
float tem;
float curadc1;
uint16_t value_V;
//软件触发使能
adc_software_trigger_enable(ADC1,ADC_INSERTED_CHANNEL);
value_V = ADC_IDATA1(ADC1);
// //电压采集
// static void ptz_Voltage_collect_adc1_task()
// {
// static float adc1_v[5];
// static unsigned char adc1_num;
// int j,k;
// float tem;
// float curadc1;
// uint16_t value_V;
// //软件触发使能
// adc_software_trigger_enable(ADC1,ADC_INSERTED_CHANNEL);
// value_V = ADC_IDATA1(ADC1);
adc1_v[adc1_num] = (float)value_V / 4096.0 * 11 *3.3;//(float)value_V;//
adc1_num++;
if(adc1_num >= 5)
{
adc1_num = 0;
for(j = 0; j < 5-1; j++)//采样值由小到大排列
{
for(k = 0; k < 5-j-1; k++)
{
if(adc1_v[k] > adc1_v[k+1])
{
tem = adc1_v[k];
adc1_v[k] = adc1_v[k+1];
adc1_v[k+1] = tem;
}
}
}
for(uint8_t i = 1; i < 5 - 1; i++)
{
curadc1 = curadc1 + adc1_v[i];
}
curadc1 = curadc1 /((float)(5 - 2));//去掉一个最大值和一个最小值求平均值
g_ptz.Voltage = curadc1;
memset(adc1_v,0,sizeof(adc1_v));
// pdebug(DEBUG_LEVEL_INFO,"get ptz Voltage: %.3fV",g_ptz.Voltage);
}
// // adc1_v[adc1_num] = (float)value_V / 4096.0 * 11 *3.38;
// adc1_v[adc1_num] = (float)value_V / 4096.0 * 12.55 *3.38;
// adc1_num++;
// if(adc1_num >= 5)
// {
// adc1_num = 0;
// for(j = 0; j < 5-1; j++)//采样值由小到大排列
// {
// for(k = 0; k < 5-j-1; k++)
// {
// if(adc1_v[k] > adc1_v[k+1])
// {
// tem = adc1_v[k];
// adc1_v[k] = adc1_v[k+1];
// adc1_v[k+1] = tem;
// }
// }
// }
// for(uint8_t i = 1; i < 5 - 1; i++)
// {
// curadc1 = curadc1 + adc1_v[i];
// }
// curadc1 = curadc1 /((float)(5 - 2));//去掉一个最大值和一个最小值求平均值
// g_ptz.Voltage = curadc1;
// memset(adc1_v,0,sizeof(adc1_v));
// // pdebug(DEBUG_LEVEL_INFO,"get ptz Voltage: %.3fV",g_ptz.Voltage);
// }
}
// }
//电流采集
static void ptz_Current_collect_adc1_task()
{
static float adc1_i[5];
static unsigned char adc0_num;
int j,k;
float tem;
float curadc0;
uint16_t value_I;
// //电流采集
// static void ptz_Current_collect_adc1_task()
// {
// static float adc1_i[5];
// static unsigned char adc0_num;
// int j,k;
// float tem;
// float curadc0;
// uint16_t value_I;
adc_software_trigger_enable(ADC1,ADC_INSERTED_CHANNEL);
value_I = ADC_IDATA0(ADC1);
// adc_software_trigger_enable(ADC1,ADC_INSERTED_CHANNEL);
// value_I = ADC_IDATA0(ADC1);
adc1_i[adc0_num] = (((float)value_I / 4096.0 * 3.3)-3.3/2) / 0.132;//(float)value_I;//
// adc1_i[adc0_num] = ((float)value_I / 4096.0 * 3.38) * 10;//(float)value_I;//
adc0_num ++;
if(adc0_num >= 5)
{
adc0_num = 0;
for(j = 0; j < 5-1; j++)//采样值由小到大排列
{
for(k = 0; k < 5-j-1; k++)
{
if(adc1_i[k] > adc1_i[k+1])
{
tem = adc1_i[k];
adc1_i[k] = adc1_i[k+1];
adc1_i[k+1] = tem;
}
}
}
for(uint8_t i = 1; i < 5 - 1; i++)
{
curadc0 = curadc0 + adc1_i[i];
}
curadc0 = curadc0 /((float)(5 - 2));//去掉一个最大值和一个最小值求平均值
g_ptz.electric_current = curadc0;
memset(adc1_i,0,sizeof(adc1_i));
// pdebug(DEBUG_LEVEL_INFO,"get ptz Electric_Current: %.3fA",g_ptz.electric_current);
}
// adc0_num ++;
// if(adc0_num >= 5)
// {
// adc0_num = 0;
// for(j = 0; j < 5-1; j++)//采样值由小到大排列
// {
// for(k = 0; k < 5-j-1; k++)
// {
// if(adc1_i[k] > adc1_i[k+1])
// {
// tem = adc1_i[k];
// adc1_i[k] = adc1_i[k+1];
// adc1_i[k+1] = tem;
// }
// }
// }
// for(uint8_t i = 1; i < 5 - 1; i++)
// {
// curadc0 = curadc0 + adc1_i[i];
// }
// curadc0 = curadc0 /((float)(5 - 2));//去掉一个最大值和一个最小值求平均值
// g_ptz.electric_current = curadc0;
// memset(adc1_i,0,sizeof(adc1_i));
// // pdebug(DEBUG_LEVEL_INFO,"get ptz Electric_Current: %.3fA",g_ptz.electric_current);
// }
}
// }
//温度采集
static void ptz_temperature_collect_tmp75_task()
{
static float tmp75[5];
static unsigned char tmp75_num;
float curtmp75;
float tem;
int j,k;
tmp75[tmp75_num] = tmp75_read_temp();
tmp75_num ++;
if(tmp75_num >= 5)
{
tmp75_num = 0;
for(j = 0; j < 5-1; j++)//采样值由小到大排列
{
for(k = 0; k < 5-j-1; k++)
{
if(tmp75[k] > tmp75[k+1])
{
tem = tmp75[k];
tmp75[k] = tmp75[k+1];
tmp75[k+1] = tem;
}
}
}
for(uint8_t i = 1; i < 5 - 1; i++)
{
curtmp75 = curtmp75 + tmp75[i];//去掉一个最大值和一个最小值
}
curtmp75 = curtmp75 / ((float)(5 - 2));
g_ptz.temperature = curtmp75;
memset(tmp75,0,sizeof(tmp75));
// pdebug(DEBUG_LEVEL_INFO,"get ptz Temperature: %.3f℃",g_ptz.temperature);
}
// //温度采集
// static void ptz_temperature_collect_tmp75_task()
// {
// static float tmp75[5];
// static unsigned char tmp75_num;
// float curtmp75;
// float tem;
// int j,k;
// tmp75[tmp75_num] = tmp75_read_temp();
// tmp75_num ++;
// if(tmp75_num >= 5)
// {
// tmp75_num = 0;
// for(j = 0; j < 5-1; j++)//采样值由小到大排列
// {
// for(k = 0; k < 5-j-1; k++)
// {
// if(tmp75[k] > tmp75[k+1])
// {
// tem = tmp75[k];
// tmp75[k] = tmp75[k+1];
// tmp75[k+1] = tem;
// }
// }
// }
// for(uint8_t i = 1; i < 5 - 1; i++)
// {
// curtmp75 = curtmp75 + tmp75[i];//去掉一个最大值和一个最小值
// }
// curtmp75 = curtmp75 / ((float)(5 - 2));
// g_ptz.temperature = curtmp75;
// memset(tmp75,0,sizeof(tmp75));
// // pdebug(DEBUG_LEVEL_INFO,"get ptz Temperature: %.3f℃",g_ptz.temperature);
// }
}
// }
//int counter;
//采集任务
@ -503,30 +493,32 @@ static char ptz_data_collect_task()
if(g_ptz.hori_start_stop_set == PTZ_HORI_START)
{//电机处于启动状态
H_ADC2_Phase_current();
// H_ADC2_Phase_current();
}
if(g_ptz.vert_start_stop_set == PTZ_VERT_START)
{//电机处于启动状态
V_ADC0_Phase_current();
// V_ADC0_Phase_current();
}
if(j >= 100)
{
j=0;
//云台不自检关闭,打开采集任务
#ifndef PTZ_NO_SELF_CHECK
#ifndef PTZ_NO_SELF_CHECK
ptz_Voltage_collect_adc1_task();
#endif
OSTimeDlyHMSM(0u, 0u, 0u, 2u);
ptz_Current_collect_adc1_task();
// OSTimeDlyHMSM(0u, 0u, 0u, 50u);
g_ptz.electric_current = ptz_Current_collect_adc1_task();
// ptz_Current_collect_adc1_task();
// OSTimeDlyHMSM(0u, 0u, 0u, 50u);
}
if(i >= 3000)
{//降低温度采集频率
ptz_temperature_collect_tmp75_task();
g_ptz.temperature = ptz_temperature_collect_tmp75_task();
//驱动电路温度采集
Ntc_value();
// Ntc_value();
i=0;
}
@ -543,7 +535,7 @@ static char ptz_data_collect_task()
static OS_STK task_data_collect_stk[TASK_PTZ_DATA_COLLECT_STK_SIZE];
static void creat_task_data_collect(void)
{
CPU_INT08U task_err;
CPU_INT08U task_err;
CPU_INT08U name_err;
task_err = OSTaskCreateExt((void (*)(void *)) ptz_data_collect_task,
@ -569,12 +561,14 @@ static void creat_task_data_collect(void)
void init_data_collect_module(void)
{
//#ifndef PTZ_NO_SELF_CHECK
ADC1_Init();//AD采集引脚初始化
// ADC1_Init();//AD采集引脚初始化
i2c_init();
adc_init();
//#endif
ADC2_Init();//AD采集引脚初始化
ADC0_Init();//AD采集引脚初始化
// ADC2_Init();//AD采集引脚初始化
// ADC0_Init();//AD采集引脚初始化
temp75_gpio_init();//温度传感器初始化
// temp75_gpio_init();//温度传感器初始化
creat_task_data_collect();
}

View File

@ -1,6 +1,19 @@
#ifndef __DEVICE_ADC_H_
#define __DEVICE_ADC_H_
#include <includes.h>
#include "gd32f4xx.h"
#include "comm_types.h"
#include "ptz_struct.h"
#include "tmp75.h"
#include "w25q128.h"
#include "agent_hyt.h"
#include "ptz_type_select.h"
#include "pdebug.h"
#include "rotate_plan.h"
#include "rotate_bldc.h"
#include "drv_adc.h"
#include "drv_i2c.h"
typedef struct _ADC_Phase_current_
{
@ -9,14 +22,14 @@ typedef struct _ADC_Phase_current_
float Phase_curr_W;
}ADC_Phase_current;
extern ADC_Phase_current H_ADC_Collect;
extern ADC_Phase_current V_ADC_Collect;
// extern ADC_Phase_current H_ADC_Collect;
// extern ADC_Phase_current V_ADC_Collect;
void ptz_send_voltage(char dev);//µçѹ»Ø´«
void ptz_send_current(char dev);//µçÁ÷»Ø´«
void ptz_send_temperature(char dev);//ζȻش«
// void ptz_send_temperature(char dev);//ζȻش«
void init_data_collect_module(void);//³õʼ»¯½Ó¿Ú
void H_ADC2_Phase_current();
void V_ADC0_Phase_current();
void ptz_send_bridge_temperature(char dev);
// void H_ADC2_Phase_current();
// void V_ADC0_Phase_current();
// void ptz_send_bridge_temperature(char dev);
#endif

File diff suppressed because it is too large Load Diff

View File

@ -4,288 +4,275 @@
#include "ptz_default_value.h"
#include "ptz_type_select.h"
#define ROTATE_FAULT_MAX_NUM 10//8 //判断转动故障连续最大次数
#define ROTATE_FAULT_MAX_NUM 10 // 8 //判断转动故障连续最大次数
//判断无法转动的模拟电压等级阈值电压
#define PTZ_HORI_VOLTAGE_LEVEL 1900.0
#define PTZ_VERT_VOLTAGE_LEVEL 1900.0
//判断无法转动速度的阈值速度
#define PTZ_HORI_DETECT_SPEED (PTZ_HORI_MIN_SPEED / 3.0)
#define PTZ_VERT_DETECT_SPEED (PTZ_VERT_MIN_SPEED / 3.0)
//故障标志
#define FAULT 1 //故障
#define NO_FAULT 0 //没有故障
// 判断无法转动的模拟电压等级阈值电压
#define PTZ_HORI_VOLTAGE_LEVEL 1900.0
#define PTZ_VERT_VOLTAGE_LEVEL 1900.0
// 判断无法转动速度的阈值速度
#define PTZ_HORI_DETECT_SPEED (PTZ_HORI_MIN_SPEED / 3.0)
#define PTZ_VERT_DETECT_SPEED (PTZ_VERT_MIN_SPEED / 3.0)
// 故障标志
#define FAULT 1 // 故障
#define NO_FAULT 0 // 没有故障
/*¹ÊÕÏÖ¸Áî´úºÅ*/
#define HORI_ROT 0X21
#define HORI_HALL 0X22
#define HORI_PDE 0X23
#define HORI_ROT 0X21
#define HORI_HALL 0X22
#define HORI_PDE 0X23
#define VERT_ROT 0X24
#define VERT_HALL 0X25
#define VERT_PDE 0X26
#define VERT_ROT 0X24
#define VERT_HALL 0X25
#define VERT_PDE 0X26
#define WORK_TEMP 0X27//温度故障
#define WORK_VOLT 0X28//电压故障
#define CAMERA_POWER 0X29//电源状态
#define WORK_TEMP 0X27 // 温度故障
#define WORK_VOLT 0X28 // 电压故障
#define CAMERA_POWER 0X29 // 电源状态
#define NTC_HORI 0X2B//水平NTC温度
#define NTC_VERT 0X2C//垂直NTC温度
#define NTC_HORI 0X2B // 水平NTC温度
#define NTC_VERT 0X2C // 垂直NTC温度
#define Phase_Curr_H 0X2D//水平相电流
#define Phase_Curr_V 0X2E//垂直相电流
#define Phase_Curr_H 0X2D // 水平相电流
#define Phase_Curr_V 0X2E // 垂直相电流
#define ALL_FAULT_STATE 0X20 // 所有都故障
#define ALL_FAULT_STATE 0X20//所有都故障
#define WORK_ELECTRIC_CURRENT 0x2A//工作电流
#define VERT_PHOTOELECT_SWITCH 0x2F//垂直光电开关
//上传云台转动方向
#define PTZ_UP 1//上
#define PTZ_DOWN 2//下
#define PTZ_LEFT 3//左
#define PTZ_RIGHT 4//右
#define WORK_ELECTRIC_CURRENT 0x2A // 工作电流
#define VERT_PHOTOELECT_SWITCH 0x2F // 垂直光电开关
// 上传云台转动方向
#define PTZ_UP 1 // 上
#define PTZ_DOWN 2 // 下
#define PTZ_LEFT 3 // 左
#define PTZ_RIGHT 4 // 右
/******************************ÔÆÌ¨¹¤×÷״̬ÅжÏ*****************************/
#define SELF_CHECKING 1//云台自检中
#define AREA_SCANING 2//区域扫描中
#define AREA_PAUSING 3//区域扫描暂停中
#define AREA_RECOING 4//区域扫描恢复中
#define AREA_CLOSING 5//区域扫描关闭中
#define PP_SCANING 6//预置位扫描中
#define PP_PAUSING 7//预置位扫描暂停中
#define PP_RECOING 8//预置位扫描恢复中
#define PP_CLOSING 9//预置位扫描关闭中
#define HORI_VREF_SAMP 10//正在进行水平电压采集
#define VERT_VREF_SAMP 11//正在进行垂直电压采集
#define HOVE_VREF_SAMP 12//水平电压采集和垂直电压同时采集
#define HORI_PD_ERROR 13//水平位置更新出错
#define VERT_PD_ERROR 14//垂直位置更新出错
#define HOVE_PD_ERROR 15//水平垂直位置更新都出错
#define MOTOR_COLD_CANNOT_ROT 16//电机低温无法转动,加热中
#define SELF_CHECKING 1 // 云台自检中
#define AREA_SCANING 2 // 区域扫描中
#define AREA_PAUSING 3 // 区域扫描暂停中
#define AREA_RECOING 4 // 区域扫描恢复中
#define AREA_CLOSING 5 // 区域扫描关闭中
#define PP_SCANING 6 // 预置位扫描中
#define PP_PAUSING 7 // 预置位扫描暂停中
#define PP_RECOING 8 // 预置位扫描恢复中
#define PP_CLOSING 9 // 预置位扫描关闭中
#define HORI_VREF_SAMP 10 // 正在进行水平电压采集
#define VERT_VREF_SAMP 11 // 正在进行垂直电压采集
#define HOVE_VREF_SAMP 12 // 水平电压采集和垂直电压同时采集
#define HORI_PD_ERROR 13 // 水平位置更新出错
#define VERT_PD_ERROR 14 // 垂直位置更新出错
#define HOVE_PD_ERROR 15 // 水平垂直位置更新都出错
#define MOTOR_COLD_CANNOT_ROT 16 // 电机低温无法转动,加热中
#define MOTOR_HORI_COLD_CANNOT_ROT 0xfa // 云台水平电机无法转动,转动故障
#define MOTOR_VERT_COLD_CANNOT_ROT 0xfb // 云台垂直电机无法转动,转动故障
#define MOTOR_HORI_CANNOT_ROT 0xfc // 云台水平电机无法转动,转动故障
#define MOTOR_VERT_CANNOT_ROT 0xfd // 云台垂直电机无法转动,转动故障
#define MOTOR_HOVE_CANNOT_ROT 0xfe // 云台所有电机无法转动,转动故障
#define OTHER_MODE 0 // 其他模式
#define MOTOR_HORI_COLD_CANNOT_ROT 0xfa//云台水平电机无法转动,转动故障
#define MOTOR_VERT_COLD_CANNOT_ROT 0xfb//云台垂直电机无法转动,转动故障
#define MOTOR_HORI_CANNOT_ROT 0xfc//云台水平电机无法转动,转动故障
#define MOTOR_VERT_CANNOT_ROT 0xfd//云台垂直电机无法转动,转动故障
#define MOTOR_HOVE_CANNOT_ROT 0xfe//云台所有电机无法转动,转动故障
#define OTHER_MODE 0 //其他模式
// 直齿轻型云台
#ifdef PTZ_LIGHT_GEAR_L6235D_AS5047D
// 工作温度阈值
#define PTZ_TEMP_DETECT_MAX 70.0 // 65.0
#define PTZ_TEMP_DETECT_MIN -40.0 //-25.0 //山火云台温度阈值-40-70
//直齿轻型云台
#ifdef PTZ_LIGHT_GEAR_L6235D_AS5047D
//工作温度阈值
#define PTZ_TEMP_DETECT_MAX 70.0 //65.0
#define PTZ_TEMP_DETECT_MIN -40.0//-25.0 //山火云台温度阈值-40-70
// 工作电压阈值
#define PTZ_VOLT_DETECT_MAX 30.0 // 30.0
#define PTZ_VOLT_DETECT_MIN 18.0 // 30.0
//工作电压阈值
#define PTZ_VOLT_DETECT_MAX 30.0//30.0
#define PTZ_VOLT_DETECT_MIN 18.0//30.0
// 工作电流阈值
#define PTZ_CURRENT_DETECT 6.0 // 5.0
//工作电流阈值
#define PTZ_CURRENT_DETECT 6.0//5.0
// 霍尔故障阈值
#define PTZ_HALL_DETECT 30 // 30
//霍尔故障阈值
#define PTZ_HALL_DETECT 30//30
//相电流运行最大值
#define PHASE_CURRENT 6.0
// 相电流运行最大值
#define PHASE_CURRENT 6.0
#endif
//L6235D蜗轮蜗杆中型云台
#ifdef PTZ_MEDIUM_WORM_L6235D_AS5047D
//工作温度阈值
#define PTZ_TEMP_DETECT_MAX 65.0 //70.0
#define PTZ_TEMP_DETECT_MIN -25.0//70.0
// L6235D蜗轮蜗杆中型云台
#ifdef PTZ_MEDIUM_WORM_L6235D_AS5047D
// 工作温度阈值
#define PTZ_TEMP_DETECT_MAX 65.0 // 70.0
#define PTZ_TEMP_DETECT_MIN -25.0 // 70.0
//工作电压阈值
#define PTZ_VOLT_DETECT_MAX 30.0//30.0
#define PTZ_VOLT_DETECT_MIN 18.0//30.0
// 工作电压阈值
#define PTZ_VOLT_DETECT_MAX 30.0 // 30.0
#define PTZ_VOLT_DETECT_MIN 18.0 // 30.0
//工作电流阈值
#define PTZ_CURRENT_DETECT 6.0//5.0
// 工作电流阈值
#define PTZ_CURRENT_DETECT 6.0 // 5.0
//霍尔故障阈值
#define PTZ_HALL_DETECT 30//30
// 霍尔故障阈值
#define PTZ_HALL_DETECT 30 // 30
//相电流运行最大值
#define PHASE_CURRENT 3.5
#endif
// 相电流运行最大值
#define PHASE_CURRENT 3.5
#endif
//L6235D涡轮蜗杆重型云台
// L6235D涡轮蜗杆重型云台
#ifdef PTZ_HEAVY_WORM_L6235D_AS5047D
//工作温度阈值
#define PTZ_TEMP_DETECT_MAX 65.0 //70.0
#define PTZ_TEMP_DETECT_MIN -25.0//70.0
// 工作温度阈值
#define PTZ_TEMP_DETECT_MAX 65.0 // 70.0
#define PTZ_TEMP_DETECT_MIN -25.0 // 70.0
//工作电压阈值
#define PTZ_VOLT_DETECT_MAX 30.0//30.0
#define PTZ_VOLT_DETECT_MIN 18.0//30.0
// 工作电压阈值
#define PTZ_VOLT_DETECT_MAX 30.0 // 30.0
#define PTZ_VOLT_DETECT_MIN 18.0 // 30.0
//工作电流阈值
#define PTZ_CURRENT_DETECT 6.0//5.0
// 工作电流阈值
#define PTZ_CURRENT_DETECT 6.0 // 5.0
//霍尔故障阈值
#define PTZ_HALL_DETECT 30//30
// 霍尔故障阈值
#define PTZ_HALL_DETECT 30 // 30
//相电流运行最大值
#define PHASE_CURRENT 5.0
#endif
// 相电流运行最大值
#define PHASE_CURRENT 5.0
#endif
#ifdef PTZ_SUPER_LIGHT_WORM_L6235D_AS5047D_12V
//工作温度阈值
#define PTZ_TEMP_DETECT_MAX 65.0 //70.0
#define PTZ_TEMP_DETECT_MIN -25.0//70.0
#ifdef PTZ_SUPER_LIGHT_WORM_L6235D_AS5047D_12V
// 工作温度阈值
#define PTZ_TEMP_DETECT_MAX 65.0 // 70.0
#define PTZ_TEMP_DETECT_MIN -25.0 // 70.0
//工作电压阈值
#define PTZ_VOLT_DETECT_MAX 14.0//30.0
#define PTZ_VOLT_DETECT_MIN 9.0//30.0
// 工作电压阈值
#define PTZ_VOLT_DETECT_MAX 14.0 // 30.0
#define PTZ_VOLT_DETECT_MIN 9.0 // 30.0
//工作电流阈值
#define PTZ_CURRENT_DETECT 6.0//5.0
// 工作电流阈值
#define PTZ_CURRENT_DETECT 6.0 // 5.0
//霍尔故障阈值
#define PTZ_HALL_DETECT 30//30
// 霍尔故障阈值
#define PTZ_HALL_DETECT 30 // 30
//相电流运行最大值
#define PHASE_CURRENT 3.0
#endif
// 相电流运行最大值
#define PHASE_CURRENT 3.0
#endif
#ifdef PTZ_SUPER_LIGHT_WORM_L6235D_AS5047D_24V
// 工作温度阈值
#define PTZ_TEMP_DETECT_MAX 65.0 // 70.0
#define PTZ_TEMP_DETECT_MIN -25.0 // 70.0
#ifdef PTZ_SUPER_LIGHT_WORM_L6235D_AS5047D_24V
//工作温度阈值
#define PTZ_TEMP_DETECT_MAX 65.0 //70.0
#define PTZ_TEMP_DETECT_MIN -25.0//70.0
// 工作电压阈值
#define PTZ_VOLT_DETECT_MAX 30.0 // 30.0
#define PTZ_VOLT_DETECT_MIN 18.0 // 30.0
//工作电压阈值
#define PTZ_VOLT_DETECT_MAX 30.0//30.0
#define PTZ_VOLT_DETECT_MIN 18.0//30.0
// 工作电流阈值
#define PTZ_CURRENT_DETECT 6.0 // 5.0
//工作电流阈值
#define PTZ_CURRENT_DETECT 6.0//5.0
// 霍尔故障阈值
#define PTZ_HALL_DETECT 30 // 30
//霍尔故障阈值
#define PTZ_HALL_DETECT 30//30
// 相电流运行最大值
#define PHASE_CURRENT 3.0
#endif
//相电流运行最大值
#define PHASE_CURRENT 3.0
#endif
//步进电机
// 步进电机
#ifdef PTZ_SUPER_LIGHT_WORM_STEP_DRV8711_AS5047D_12V
//工作温度阈值
#define PTZ_TEMP_DETECT_MAX 65.0 //70.0
#define PTZ_TEMP_DETECT_MIN -25.0//70.0
// 工作温度阈值
#define PTZ_TEMP_DETECT_MAX 65.0 // 70.0
#define PTZ_TEMP_DETECT_MIN -25.0 // 70.0
//工作电压阈值
#define PTZ_VOLT_DETECT_MAX 14.0//30.0
#define PTZ_VOLT_DETECT_MIN 9.0//30.0
// 工作电压阈值
#define PTZ_VOLT_DETECT_MAX 14.0 // 30.0
#define PTZ_VOLT_DETECT_MIN 9.0 // 30.0
//工作电流阈值
#define PTZ_CURRENT_DETECT 6.0//5.0
// 工作电流阈值
#define PTZ_CURRENT_DETECT 6.0 // 5.0
#endif
//步进电机
// 步进电机
#ifdef PTZ_SUPER_LIGHT_WORM_STEP_DRV8711_AS5047D_24V
//工作温度阈值
#define PTZ_TEMP_DETECT_MAX 65.0 //70.0
#define PTZ_TEMP_DETECT_MIN -25.0//70.0
// 工作温度阈值
#define PTZ_TEMP_DETECT_MAX 65.0 // 70.0
#define PTZ_TEMP_DETECT_MIN -25.0 // 70.0
//工作电压阈值
#define PTZ_VOLT_DETECT_MAX 30.0//30.0
#define PTZ_VOLT_DETECT_MIN 9.0//30.0
// 工作电压阈值
#define PTZ_VOLT_DETECT_MAX 30.0 // 30.0
#define PTZ_VOLT_DETECT_MIN 9.0 // 30.0
//工作电流阈值
#define PTZ_CURRENT_DETECT 6.0//5.0
// 工作电流阈值
#define PTZ_CURRENT_DETECT 6.0 // 5.0
#endif
//步进电机
// 步进电机
#ifdef PTZ_SUPER_LIGHT_WORM_STEP_TMC2160_AS5047D_24V
//工作温度阈值
#define PTZ_TEMP_DETECT_MAX 65.0 //70.0
#define PTZ_TEMP_DETECT_MIN -25.0//70.0
// 工作温度阈值
#define PTZ_TEMP_DETECT_MAX 65.0 // 70.0
#define PTZ_TEMP_DETECT_MIN -25.0 // 70.0
//工作电压阈值
#define PTZ_VOLT_DETECT_MAX 30.0//30.0
#define PTZ_VOLT_DETECT_MIN 9.0//30.0
// 工作电压阈值
#define PTZ_VOLT_DETECT_MAX 30.0 // 30.0
#define PTZ_VOLT_DETECT_MIN 9.0 // 30.0
//工作电流阈值
#define PTZ_CURRENT_DETECT 6.0//5.0
// 工作电流阈值
#define PTZ_CURRENT_DETECT 6.0 // 5.0
#endif
//中型步进电机
// 中型步进电机
#ifdef PTZ_MEDIUM_WORM_STEP_TMC2160_AS5047D_24V
//工作温度阈值
#define PTZ_TEMP_DETECT_MAX 65.0 //70.0
#define PTZ_TEMP_DETECT_MIN -25.0//70.0
// 工作温度阈值
#define PTZ_TEMP_DETECT_MAX 65.0 // 70.0
#define PTZ_TEMP_DETECT_MIN -25.0 // 70.0
//工作电压阈值
#define PTZ_VOLT_DETECT_MAX 30.0//30.0
#define PTZ_VOLT_DETECT_MIN 9.0//30.0
// 工作电压阈值
#define PTZ_VOLT_DETECT_MAX 30.0 // 30.0
#define PTZ_VOLT_DETECT_MIN 9.0 // 30.0
//工作电流阈值
#define PTZ_CURRENT_DETECT 6.0//5.0
// 工作电流阈值
#define PTZ_CURRENT_DETECT 6.0 // 5.0
#endif
//伺服电机
// 伺服电机
#ifdef PTZ_MEDIUM_WORM_SERVO_MOTOR_24V
//工作温度阈值
#define PTZ_TEMP_DETECT_MAX 65.0 //70.0
#define PTZ_TEMP_DETECT_MIN -25.0//70.0
// 工作温度阈值
#define PTZ_TEMP_DETECT_MAX 65.0 // 70.0
#define PTZ_TEMP_DETECT_MIN -25.0 // 70.0
//工作电压阈值
#define PTZ_VOLT_DETECT_MAX 30.0//30.0
#define PTZ_VOLT_DETECT_MIN 9.0//30.0
// 工作电压阈值
#define PTZ_VOLT_DETECT_MAX 30.0 // 30.0
#define PTZ_VOLT_DETECT_MIN 9.0 // 30.0
//工作电流阈值
#define PTZ_CURRENT_DETECT 10.0//5.0
// 工作电流阈值
#define PTZ_CURRENT_DETECT 10.0 // 5.0
#endif
///需要判断能否执行的指令
/// 需要判断能否执行的指令
typedef struct _PtzCmdType_
{//当参数为1时表示该指令能够执行0表示不能够被执行
char manual_control;//手动控制,包括上下左右等方向控制,和角度控制
{ // 当参数为1时表示该指令能够执行0表示不能够被执行
char manual_control; // 手动控制,包括上下左右等方向控制,和角度控制
char manual_stop;//手动停止指令
char preset_bit_set;//预置位设置
char preset_bit_del;//预置位删除
char preset_bit_call;//预置位调用
char preset_bit_scan_start;//预置位扫描启动
char preset_bit_scan_pause;//预置位扫描暂停
char preset_bit_scan_recovery;//预置位扫描恢复
char preset_bit_scan_close;//预置位扫描关闭
char area_set;//区域数据设置
char area_scan_start;//区域扫描启动
char area_scan_pause;//区域扫描暂停
char area_scan_recovery;//区域扫描恢复
char area_scan_close;//区域扫描关闭
char set_zero;//设置0位
char manual_stop; // 手动停止指令
}PtzCmdType;
char preset_bit_set; // 预置位设置
char preset_bit_del; // 预置位删除
char preset_bit_call; // 预置位调用
char preset_bit_scan_start; // 预置位扫描启动
char preset_bit_scan_pause; // 预置位扫描暂停
char preset_bit_scan_recovery; // 预置位扫描恢复
char preset_bit_scan_close; // 预置位扫描关闭
//云台工作模式判断
char area_set; // 区域数据设置
char area_scan_start; // 区域扫描启动
char area_scan_pause; // 区域扫描暂停
char area_scan_recovery; // 区域扫描恢复
char area_scan_close; // 区域扫描关闭
char set_zero; // 设置0位
} PtzCmdType;
// 云台工作模式判断
typedef struct _PtzWorkMode_
{
char mode;
char data_a;
char data_b;
}PtzWorkMode;
char mode;
char data_a;
char data_b;
} PtzWorkMode;
PtzWorkMode ptz_work_mode_judge();
PtzCmdType ptz_cmd_execute_judge();

View File

@ -1012,19 +1012,6 @@ TMR3109_Device tmr3109_dev2 = {
TMR3109_AngleData hori_angle_data = {0};
TMR3109_AngleData vert_angle_data = {0};
//暂定微秒级延迟函数(基于SysTick)(后期删除,所有延迟函数更换为统一的函数)
void delay_us(uint32_t us)
{
uint32_t start, now, delta, reload, us_tick;
start = SysTick->VAL;
reload = SysTick->LOAD;
us_tick = SystemCoreClock / 1000000UL;
do {
now = SysTick->VAL;
delta = start > now? start - now : reload + start - now;
} while (delta < us_tick * us);
}
//TMR3109³õʼ»¯
void TMR3109_Init(void)

View File

@ -1,6 +1,7 @@
#ifndef __AS5047D_H_
#define __AS5047D_H_
#include "gd32f4xx.h"
#include "delay.h"
#define TMR3109 1

32
BSP/Driver/delay.c Normal file
View File

@ -0,0 +1,32 @@
#include "delay.h"
/*
@ brief
@ param
@ return
@ note 2022-5-23
*/
void delay_us(int us)//100us以内
{
uint32_t start, now, delta, reload, us_tick;
start = SysTick->VAL;//记录进入函数时SysTick计数器的当前值。
reload = SysTick->LOAD;//SysTick的重载值即计数器从reload递减到0。
/* 240 */
us_tick = SystemCoreClock / 1000000UL;//每微秒对应的滴答数系统时钟频率除以1000000。SystemCoreClock是系统核心时钟频率单位Hz除以1000000得到每微秒的滴答数。
do
{
now = SysTick->VAL;//在循环中不断读取的SysTick当前值。
delta = start > now ? start - now : reload + start - now;//计算从start到now的时间间隔以滴答数计
} while (delta < us_tick * us);//直到经过的滴答数大于等于所需的微秒数对应的滴答数才退出。
}
void delay_ms(int ms)
{
for (int i = 0; i < ms; i++)
{
for (int j = 0; j < 1000; j++)
{
delay_us(1);
}
}
}

10
BSP/Driver/delay.h Normal file
View File

@ -0,0 +1,10 @@
#ifndef DELAY_H
#define DELAY_H
#include "gd32f4xx.h"
void delay_us(int us);
void delay_ms(int ms);
#endif

377
BSP/Driver/drv_adc.c Normal file
View File

@ -0,0 +1,377 @@
/************************************************************
Copyright (C), 2025, cerlink Tech. Co., Ltd.
FileName: drv_adc.c
Author: dufresne Version : 1.0 Date:2025.09.15
Description: // 模块描述
Version: // 版本信息
Function List: // 主要函数及其功能
1. -------
History: // 历史修改记录
<author> <time> <version > <desc>
David 96/10/12 1.0 build this moudle
***********************************************************/
#include "drv_adc.h"
#ifdef DMAX
/*全局声明区*/
uint16_t USER_ADC_DMA_DATA_BUFF[16] = {0};
#endif
float adc1_v[LB_V_TIMES];
float curadc1_out_v;
uint8_t adc1_v_num = 0;
float adc1_i[LB_I_TIMES];
float curadc1_out_i;
uint8_t adc1_i_num = 0;
float tmp75[LB_T_TIMES];
float curtmp75_out;
uint8_t tmp75_num;
bool filter_v_flag = 0;//滤波开启标志位,全局改变一次
bool filter_i_flag = 0;//滤波开启标志位,全局改变一次
bool filter_t_flag = 0;//滤波开启标志位,全局改变一次
/* ---------------------------------------------------配置---------------------------------------------------- */
void adc_init(void)
{
adc_rcu_config();
adc_gpio_config();
#ifdef DMAX
adc_dma_config();
#endif
adc_config();
#ifdef ADCX_IRQn
adc_interrupt_int();
#endif
}
/* 时钟+GPIO */
void adc_rcu_config(void)
{
/* 启用ADC1时钟 */
rcu_periph_clock_enable(RCU_ADC1);
#ifdef DMAX
/* peripheral clock enable */
rcu_periph_clock_enable(RCU_DMA1);//ADC只能用DMA1
#endif
/* 启用GPIOC时钟 */
rcu_periph_clock_enable(RCU_GPIOC);
adc_clock_config(ADC_ADCCK_PCLK2_DIV4);
}
void adc_gpio_config(void)
{
/* 配置ADC引脚为模拟输入模式 */
gpio_mode_set(ADC_GPIO_PORT, GPIO_MODE_ANALOG, GPIO_PUPD_NONE, VOLTAGE_ADC_PIN);
gpio_mode_set(ADC_GPIO_PORT, GPIO_MODE_ANALOG, GPIO_PUPD_NONE, CURRENT_ADC_PIN);
}
#ifdef DMAX
/* DMA配置 */
void adc_dma_config(void)
{
/* ADC_DMA_channel configuration */
dma_single_data_parameter_struct dma_single_data_parameter; //这里使用单数据模式,每次只传输一个数据单元,因为总数据量不大,且数据个数不固定
/* ADC DMA_channel configuration */
dma_deinit (DMA1, USER_DMA_ADC_CHANNEL);
/* initialize DMA single data mode */
dma_single_data_parameter.periph_addr = (uint32_t)(&ADC_RDATA(ADCX)); //配置外设数据源地址宏决定ADCx
dma_single_data_parameter.periph_inc = DMA_PERIPH_INCREASE_DISABLE; //关闭外设增量,只需要每次对该数据源寄存器访问
dma_single_data_parameter.memory0_addr = (uint32_t)USER_ADC_DMA_DATA_BUFF; //先写死然后外部用的话需要extern
dma_single_data_parameter.memory_inc = DMA_MEMORY_INCREASE_ENABLE; //开启内存增量以存放不同通道的ADC数据
dma_single_data_parameter.periph_memory_width = DMA_PERIPH_WIDTH_16BIT; //ADC数据为16位的寄存器数据目的地为16位
dma_single_data_parameter.circular_mode = DMA_CIRCULAR_MODE_ENABLE; //循环模式由ADC通知DMA进行
dma_single_data_parameter.direction = DMA_PERIPH_TO_MEMORY; //ADC外设到RAM全局变量 DMA外设到内存模式开启
dma_single_data_parameter.number = CHANNEL_LENGTH; //宏决定传输个数
dma_single_data_parameter.priority = DMA_PRIORITY_ULTRA_HIGH; //优先级设为超高,可改用宏
dma_single_data_mode_init (DMAX, USER_DMA_ADC_CHANNEL, &dma_single_data_parameter);
/* 配置 dma 子连接 */
dma_channel_subperipheral_select (DMAX, USER_DMA_ADC_CHANNEL, USER_DMA_ADC_SUBPERI);
/* enable DMA circulation mode */
dma_circulation_enable (DMAX, USER_DMA_ADC_CHANNEL);// 开启循环模式
/* enable DMA it */
dma_interrupt_enable (DMAX,USER_DMA_ADC_CHANNEL,DMA_INT_FTF);//DMA传输完成标志位 打开全部完成中断 4
// dma_interrupt_enable (DMAX,USER_DMA_ADC_CHANNEL,DMA_INT_TAE);//传输错误中断使能位 2
// dma_interrupt_enable (DMAX,USER_DMA_ADC_CHANNEL,DMA_INT_FEE);// 7
nvic_irq_enable (DMA_ADC_IRQn, DMA_ADC_PRIORITY_PRE, DMA_ADC_PRIORITY_SUB);
dma_channel_enable (DMAX, USER_DMA_ADC_CHANNEL);// enable DMA channel
}
/**
* @brief ADC测量值
* @param ADC通道结构体中的成员序号
* @return
*/
uint16_t BSP_ADCDataAcquire(uint8_t _index)
{
return USER_ADC_DMA_DATA_BUFF[_index];
}
/*
*****************************************************************************
* : DMA1_Channel0_IRQHandler
* : DMA_ADC中断服务回调函数
* :
* :
*****************************************************************************
*/
__weak void DMA1_Channel0_IRQHandler(void)
{
}
#endif
void adc_config(void)
{
adc_deinit();// 复位ADC配置可选但建议初始化时做一次
adc_special_function_config (ADCX, ADC_SCAN_MODE, SCAN_STATUS);// 扫描模式
adc_special_function_config (ADCX, ADC_CONTINUOUS_MODE, CONTINUOUS_STATUS);// 连续模式
adc_data_alignment_config (ADCX, ADC_DATAALIGN_RIGHT);// 配置数据对齐方式为右对齐
adc_resolution_config (ADCX, ADC_RESOLUTION_12B);// 配置ADC分辨率12位
/* 设置转换通道序列 */
adc_channel_length_config (ADCX, SEQUENCE_CHANNEL, CHANNEL_LENGTH);// 配置规则序列的长度2个通道
if (SEQUENCE_CHANNEL == ADC_INSERTED_CHANNEL)
{
//通道注入顺序
/* 配置规则序列序号0是电压通道序号1是电流通道 */
adc_inserted_channel_config (ADCX, 0, VOLTAGE_ADC_CHANNEL, ADC_SAMPLETIME_480);//电压
adc_inserted_channel_config (ADCX, 1, CURRENT_ADC_CHANNEL, ADC_SAMPLETIME_480);//电流
}
#ifdef DMAX
adc_regular_channel_config(ADCX, 0, VOLTAGE_ADC_CHANNEL, ADC_SAMPLETIME_480);
adc_regular_channel_config(ADCX, 1, CURRENT_ADC_CHANNEL, ADC_SAMPLETIME_480);
#endif
/* 使能外部触发:这里使用软件触发,所以先禁用硬件触发 */
// adc_external_trigger_source_config(ADCX, SEQUENCE_CHANNEL, ADC_EXTTRIG_ROUTINE_T0_CH0);
adc_external_trigger_config (ADCX, SEQUENCE_CHANNEL, DISABLE);
#ifdef DMAX
/* ADC dma config */
adc_dma_request_after_last_enable (ADCX);
adc_dma_mode_enable (ADCX);
#endif
adc_enable (ADCX); // 开启ADC
// rt_thread_mdelay(50); // 等待ADC稳定后续接校准
delay_ms(50);
adc_calibration_enable (ADCX); // 执行ADC自校准
#ifdef DMAX
adc_software_trigger_enable (ADCX, SEQUENCE_CHANNEL); // 软件触发使能 后续接读取
#endif
}
#ifdef ADCX_IRQn
void adc_interrupt_int(void)
{
adc_interrupt_enable (ADCX, ADC_INT_EOC);
nvic_irq_enable (ADCX_IRQn, ADCX_PRIORITY_PRE, ADCX_PRIORITY_SUB);
}
#endif
/* ---------------------------------------------------采集---------------------------------------------------- */
// adc电压采集
float ptz_Voltage_collect_adc1_task()
{
uint16_t value_V = 0;
#ifdef ADC_MODE_0
/* 模式1需先配置 */
adc_regular_channel_config(ADCX, 0, VOLTAGE_ADC_CHANNEL, ADC_SAMPLETIME_480);
#endif
#if (defined ADC_MODE_0) || (defined ADC_MODE_1)
/* 模式1 + 2 */
adc_software_trigger_enable(ADCX, SEQUENCE_CHANNEL);// 软件触发使能 后续接读取
#endif
#ifdef ADC_MODE_0
while(adc_flag_get(ADCX, ADC_FLAG_EOC) == RESET); // 等待转换结束
adc_flag_clear(ADCX, ADC_FLAG_EOC);
value_V = adc_regular_data_read(ADCX); // 读取规则组数据寄存器
#endif
#ifdef ADC_MODE_1
while(adc_flag_get(ADCX, ADC_FLAG_EOIC) == RESET); // 等待转换结束
adc_flag_clear(ADCX, ADC_FLAG_EOIC);
value_V = adc_inserted_data_read(ADCX, ADC_INSERTED_CHANNEL_0); // 读取注入组数据寄存器
#endif
#ifdef ADC_MODE_3
value_V = BSP_ADCDataAcquire(0);
#endif
/* 间接测量11倍分压/放大 */
adc1_v[adc1_v_num] = (float)value_V / 4096.0 * 3.381 * 12.55;
adc1_v_num++;
if(adc1_v_num >= LB_V_TIMES)
{
adc1_v_num = 0;
filter_v_flag = 1;
}
if (filter_v_flag)//等读满一组开始滤波
{
return Filtering(adc1_v, LB_V_TIMES, LB_V_DEL);
}
return 0;
}
// adc电流采集
float ptz_Current_collect_adc1_task()
{
uint16_t value_I = 0;
#ifdef ADC_MODE_0
/* 模式1需先配置 */
adc_regular_channel_config(ADCX, 0, CURRENT_ADC_CHANNEL, ADC_SAMPLETIME_480);
#endif
#if (defined ADC_MODE_0) || (defined ADC_MODE_1)
/* 模式1 + 2 */
adc_software_trigger_enable(ADCX, SEQUENCE_CHANNEL);// 软件触发使能 后续接读取
#endif
#ifdef ADC_MODE_0
while(adc_flag_get(ADCX, ADC_FLAG_EOC) == RESET); // 等待转换结束
adc_flag_clear(ADCX, ADC_FLAG_EOC);
value_I = adc_regular_data_read(ADCX); // 读取规则组数据寄存器
#endif
#ifdef ADC_MODE_1
while(adc_flag_get(ADCX, ADC_FLAG_EOIC) == RESET); // 等待转换结束
adc_flag_clear(ADCX, ADC_FLAG_EOIC);
value_I = adc_inserted_data_read(ADCX, ADC_INSERTED_CHANNEL_1); // 读取注入组数据寄存器
#endif
#ifdef ADC_MODE_3
value_I = BSP_ADCDataAcquire(1);
#endif
/* 间接测量 */
adc1_i[adc1_i_num] = ((float)value_I / 4096.0 * 3.381) * 10;
adc1_i_num++;
if(adc1_i_num >= LB_I_TIMES)
{
adc1_i_num = 0;
filter_i_flag = 1;
}
if (filter_i_flag)
{
return Filtering(adc1_i, LB_I_TIMES, LB_I_DEL);
}
return 0;
}
/* 温度采集 */
float ptz_temperature_collect_tmp75_task()
{
#ifdef HARDWARE_I2C
uint8_t tempHL[2];
uint16_t tempCode = 0;
float temp = 0;
uint8_t temp_addr[1] = {TEMP_REGISTER_ADDRESS};
i2c_write(temp_addr, 1, TMP75_ADDRESS);
i2c_read(tempHL, 2, TMP75_ADDRESS);
tempCode = (tempHL[0] << 8) | tempHL[1];
tempCode = tempCode >> 6;
if (tempCode & 0x200) // 负温度
{
tempCode &= 0x1ff;
temp = ((float)tempCode - 512) / 4;
}
else
{
temp = (float)tempCode / 4;
}
tmp75[tmp75_num] = temp;
#endif
#ifdef SOFTWARE_I2C
tmp75[tmp75_num] = tmp75_read_temp();
#endif
tmp75_num ++;
if(tmp75_num >= LB_T_TIMES)
{
tmp75_num = 0;
filter_t_flag = 1;
}
if (filter_t_flag)
{
return Filtering(tmp75, LB_T_TIMES, LB_T_DEL);
}
return 0;
}
/* 滤波函数 */
float Filtering(float *filter, uint8_t filterlens, uint8_t filterdel)
{
uint8_t j,k;
float tem;
float curadc = 0;
for(j = 0; j < filterlens - 1; j++)// 采样值由小到大排列
{
for(k = 0; k < filterlens - j - 1; k++)
{
if(filter[k] > filter[k + 1])
{
tem = filter[k];
filter[k] = filter[k + 1];
filter[k + 1] = tem;
}
}
}
for(uint8_t i = filterdel; i < filterlens - filterdel; i++)
{
curadc = curadc + filter[i];
}
curadc = curadc / ((float)(filterlens - filterdel * 2));// 去掉一个最大值和一个最小值求平均值
return curadc;
}

121
BSP/Driver/drv_adc.h Normal file
View File

@ -0,0 +1,121 @@
#ifndef __DRV_ADC_H_
#define __DRV_ADC_H_
#include "tmp75.h"
#include "drv_i2c.h"
#include "stdlib.h"
#include "stdbool.h"
#include "string.h"
#include "gd32f4xx.h"
#include "delay.h"
/* 自定义宏,方便修改通道和引脚 */
#define ADCX ADC1
#define VOLTAGE_ADC_CHANNEL ADC_CHANNEL_12
#define CURRENT_ADC_CHANNEL ADC_CHANNEL_13
#define ADC_GPIO_PORT GPIOC
#define VOLTAGE_ADC_PIN GPIO_PIN_2
#define CURRENT_ADC_PIN GPIO_PIN_3
#define LB_V_TIMES 6 //电压采样、滤波次数
#define LB_I_TIMES 6 //电流采样、滤波次数
#define LB_T_TIMES 3 //温度采样、滤波次数
#define LB_V_DEL 1 //电压滤波最高最低各删除个数
#define LB_I_DEL 2 //电流滤波最高最低各删除个数
#define LB_T_DEL 1 //温度滤波最高最低各删除个数
#define ADC_MODE_0 //规则组、单次转换、非扫描
// #define ADC_MODE_1 //注入组、单次转换、扫描、转换结束标志位采集
// #define ADC_MODE_2 //注入组、单次转换、扫描、中断转换结束标志位采集
// #define ADC_MODE_3 //规则组、连续转换、扫描、DMA采集
/* adc模式配置参数ENABLEDISABLE */
#ifdef ADC_MODE_0
#define CONTINUOUS_STATUS DISABLE // 是否开启连续转换
#define SEQUENCE_CHANNEL ADC_REGULAR_CHANNEL // 规则组
#define SCAN_STATUS DISABLE // 是否开启扫描模式
#define CHANNEL_LENGTH 1 // 通道数量:1~16
#endif
#ifdef ADC_MODE_1
#define CONTINUOUS_STATUS DISABLE // 是否开启连续转换
#define SEQUENCE_CHANNEL ADC_INSERTED_CHANNEL // 注入组
#define SCAN_STATUS ENABLE // 是否开启扫描模式
#define CHANNEL_LENGTH 2 // 通道数量:1~16
#endif
#ifdef ADC_MODE_2
#define CONTINUOUS_STATUS DISABLE // 不开启连续转换
#define SEQUENCE_CHANNEL ADC_INSERTED_CHANNEL // 注入组
#define SCAN_STATUS ENABLE // 是否开启扫描模式
#define CHANNEL_LENGTH 2 // 通道数量:1~16
#define ADCX_IRQn ADC_IRQn
#endif
#ifdef ADC_MODE_3
#define CONTINUOUS_STATUS ENABLE // 开启连续转换
#define SEQUENCE_CHANNEL ADC_REGULAR_CHANNEL // 规则组
#define SCAN_STATUS ENABLE // 是否开启扫描模式
#define CHANNEL_LENGTH 2 // 通道数量:1~16
#define DMAX DMA1
#endif
/* adc dma */
#ifdef DMAX
#define USER_DMA_ADC_CHANNEL DMA_CH3 //DMA通道ADC0:DMA_CH0 DMA_CH4
// ADC1:DMA_CH2 DMA_CH3
// ADC2:DMA_CH0 DMA_CH3
#define USER_DMA_ADC_SUBPERI DMA_SUBPERI1 //DMA外设源:ADC0:DMA_SUBPERI0
// ADC1:DMA_SUBPERI1
// ADC2:DMA_SUBPERI2
#define DMA_ADC_IRQn DMA1_Channel0_IRQn //DMA1_Channel0_IRQn
//DMA1_Channel1_IRQn
//DMA1_Channel2_IRQn
//DMA1_Channel3_IRQn
//DMA1_Channel4_IRQn
#define DMA_ADC_PRIORITY_PRE 0 //抢占优先级
#define DMA_ADC_PRIORITY_SUB 1 //子优先级
#endif
#ifdef ADCX_IRQn
#define ADCX_PRIORITY_PRE 2U //抢占优先级
#define ADCX_PRIORITY_SUB 0U //子优先级
#endif
void adc_init(void);
void adc_rcu_config(void);
void adc_gpio_config(void);
void adc_config(void);
float ptz_Voltage_collect_adc1_task();
float ptz_Current_collect_adc1_task();
float ptz_temperature_collect_tmp75_task();
float Filtering(float *filter, uint8_t filterlens, uint8_t filterdel);
#ifdef ADCX_IRQn
void adc_interrupt_int(void);
#endif
#ifdef DMAX
void adc_dma_config(void);
__weak void DMA1_Channel0_IRQHandler(void);
uint16_t BSP_ADCDataAcquire(uint8_t _index);
#endif
#endif

171
BSP/Driver/drv_i2c.c Normal file
View File

@ -0,0 +1,171 @@
/*************************************************
Copyright (c) 2025,
All rights reserved.
@file drv_i2c.C
@brief drv_i2c驱动程序
@details
@note
@author dufresne
@date 2025/09/24
@version v1.0 2025/09/24
*************************************************/
#include "drv_i2c.h"
void i2c_init(void)
{
i2c_gpio_config();
#ifdef HARDWARE_I2C
i2c_config();
#endif
}
/*
@ brief i2c的GPIO引脚
@ param
@ return
@ note 2025-09-15
*/
void i2c_gpio_config(void)
{
// 配置引脚时钟
rcu_periph_clock_enable(RCU_GPIOB);
#ifdef HARDWARE_I2C
gpio_af_set(GPIOB, GPIO_AF_4, I2C_SCL_PIN | I2C_SDA_PIN);
/* 初始化GPIO复用功能模式 */
gpio_mode_set(GPIOB, GPIO_MODE_AF, GPIO_PUPD_PULLUP, I2C_SCL_PIN | I2C_SDA_PIN);
gpio_output_options_set(GPIOB, GPIO_OTYPE_OD, GPIO_OSPEED_50MHZ, I2C_SCL_PIN | I2C_SDA_PIN);
#endif
#ifdef SOFTWARE_I2C
// 设置引脚为输出模式:PB6
gpio_mode_set(GPIOB, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, I2C_SCL_PIN | I2C_SDA_PIN);
gpio_output_options_set(GPIOB, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, I2C_SCL_PIN | I2C_SDA_PIN);
I2C_SCL_HIGH;
I2C_SDA_HIGH;
#endif
}
#ifdef HARDWARE_I2C
void i2c_config(void)
{
// 启用 I2C 外设的时钟
rcu_periph_clock_enable(RCU_I2C0);
i2c_deinit(I2C_PERIPH);
// 配置 I2C 的时钟参数:
// I2C_PERIPH这里使用的I2C1
// I2C_SPEED通信速率单位为 Hz常用为 100000 或 400000这里使用100000
i2c_clock_config(I2C_PERIPH, I2C_SPEED, I2C_DTCY_2);
// 配置 I2C 工作模式和地址:
// I2C_ADDFORMAT_7BITS使用 7 位地址模式
i2c_mode_addr_config(I2C_PERIPH, I2C_I2CMODE_ENABLE, I2C_ADDFORMAT_7BITS, 0x00);//作为从机时的地址,随意设置即可
// 使能 ACK 应答功能,确保在接收数据后自动发送 ACK
i2c_ack_config(I2C_PERIPH, I2C_ACK_ENABLE);
// 启用 I2C 外设
i2c_enable(I2C_PERIPH);
}
void i2c_write(uint8_t *buff, int len, uint8_t device_address)
{
/* 等待总线空闲 */
while(i2c_flag_get(I2C_PERIPH, I2C_FLAG_I2CBSY));
/* 发送起始条件 */
i2c_start_on_bus(I2C_PERIPH);
/* 等待起始条件已发送标志 */
while(!i2c_flag_get(I2C_PERIPH, I2C_FLAG_SBSEND));
/* 发送从机地址(写模式) */
i2c_master_addressing(I2C_PERIPH, device_address << 1, I2C_TRANSMITTER);
/* 等待地址已发送标志 */
while(!i2c_flag_get(I2C_PERIPH, I2C_FLAG_ADDSEND));
/* 清除地址发送标志 */
i2c_flag_clear(I2C_PERIPH, I2C_FLAG_ADDSEND);
for(int i = 0; i < len; i++)
{
/* 等待发送数据缓冲区为空 */
while(!i2c_flag_get(I2C_PERIPH, I2C_FLAG_TBE));
/* 发送一个字节数据 */
i2c_data_transmit(I2C_PERIPH, buff[i]);
}
/* 等待数据传输完成 */
while(!i2c_flag_get(I2C_PERIPH, I2C_FLAG_TBE));
/* 发送停止条件 */
i2c_stop_on_bus(I2C_PERIPH);
/* 等待停止条件发送完成 */
while(I2C_CTL0(I2C_PERIPH) & I2C_CTL0_STOP); // 检查STPDET位或类似标志
}
//接收1字节数据
void i2c_read(uint8_t *buff, uint16_t len, uint8_t device_address)
{
/* 等待I2C总线空闲 */
while(i2c_flag_get(I2C_PERIPH, I2C_FLAG_I2CBSY));
/* 向I2C总线发送启动信号 */
i2c_start_on_bus(I2C_PERIPH);
/* 等待直到设置SBSEND位 */
while(!i2c_flag_get(I2C_PERIPH, I2C_FLAG_SBSEND));//设置主机发送启动条件
/* 将从机地址发送到I2C总线 */
i2c_master_addressing(I2C_PERIPH, device_address << 1, I2C_RECEIVER);//设置主机接收
/* 等待地址位被设置 */
while(!i2c_flag_get(I2C_PERIPH, I2C_FLAG_ADDSEND));
/* 清除地址位 */
i2c_flag_clear(I2C_PERIPH, I2C_FLAG_ADDSEND);
/* 使能ACK多个字节接收时需要应答 */
i2c_ack_config(I2C_PERIPH, I2C_ACK_ENABLE);
/* 5. 接收数据 */
if(len > 1)
{
/* 使能ACK多个字节接收时需要应答 */
i2c_ack_config(I2C_PERIPH, I2C_ACK_ENABLE);
for(int i = 0; i < len; i++)
{
if(i == (len - 1))
{
/* 最后一个字节前禁用ACK */
i2c_ack_config(I2C_PERIPH, I2C_ACK_DISABLE);
}
/* 等待RBNE标志接收缓冲区非空 */
while(!i2c_flag_get(I2C_PERIPH, I2C_FLAG_RBNE));
/* 读取数据 */
buff[i] = i2c_data_receive(I2C_PERIPH);
}
}
else
{
/* 单字节接收直接禁用ACK */
i2c_ack_config(I2C_PERIPH, I2C_ACK_DISABLE);
/* 等待RBNE标志 */
while(!i2c_flag_get(I2C_PERIPH, I2C_FLAG_RBNE));
/* 读取数据 */
buff[0] = i2c_data_receive(I2C_PERIPH);
}
/* 发送停止信号 */
i2c_stop_on_bus(I2C_PERIPH);
/* 等待停止信号完成 */
while(I2C_CTL0(I2C_PERIPH) & I2C_CTL0_STOP);
}
#endif

51
BSP/Driver/drv_i2c.h Normal file
View File

@ -0,0 +1,51 @@
///Copyright (c) 2022, 四川汇源光通信有限公司
///All rights reserved.
///@file drv_i2c.h
///@brief drv_i2c驱动程序
///
///@details
///@note
///@author dufresne
///@date 2025/09/24
///
///@version v1.0 2025/09/24 初始版本
#ifndef DRV_I2C_H
#define DRV_I2C_H
#include "gd32f4xx.h"
#include "delay.h"
// #define SOFTWARE_I2C
#define HARDWARE_I2C
#define I2C_SCL_PIN GPIO_PIN_6
#define I2C_SDA_PIN GPIO_PIN_7
#define TMP75_ADDRESS 0x48 //1001000
#define TEMP_REGISTER_ADDRESS 0x00 //tmp75寄存器温度数据地址
#ifdef HARDWARE_I2C
#define I2C_PERIPH I2C0
#define I2C_SPEED 100000
#endif
#define I2C_SCL_HIGH gpio_bit_set(GPIOB, I2C_SCL_PIN)
#define I2C_SCL_LOW gpio_bit_reset(GPIOB, I2C_SCL_PIN)
#define I2C_SDA_HIGH gpio_bit_set(GPIOB, I2C_SDA_PIN)
#define I2C_SDA_LOW gpio_bit_reset(GPIOB, I2C_SDA_PIN)
#define I2C_SDA_GET gpio_input_bit_get(GPIOB, I2C_SDA_PIN)
void i2c_init(void);
void i2c_gpio_config(void);
#ifdef HARDWARE_I2C
void i2c_config(void);
void i2c_write(uint8_t *buff, int len, uint8_t device_address);
void i2c_read(uint8_t *buff, uint16_t len, uint8_t device_address);
#endif
#endif

View File

@ -5,68 +5,14 @@
///
///@details
///@note
///@author lqc
///@date 2022/05/26
///@author dufresne
///@date 2025/09/26
///
///@version v1.0 2022/05/26 初始版本
#include "mb85rc64.h"
/*
@ brief
@ param
@ return
@ note 2022-5-23
*/
static void delay_us(int us)
{
for(int i = 0; i < us; i++ )
{
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
}
}
/*
@ brief
@ param
@ return
@ note 2022-05-26
*/
void mb85rc64_gpio_init()
{
//配置引脚时钟
rcu_periph_clock_enable(RCU_GPIOB);
//设置引脚为输出模式:PB6
gpio_mode_set(GPIOB, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, GPIO_PIN_6);
gpio_output_options_set(GPIOB, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, GPIO_PIN_6);
//设置引脚PB7输出模式
gpio_mode_set(GPIOB, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, GPIO_PIN_7);
gpio_output_options_set(GPIOB, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, GPIO_PIN_7);
MB85RC64_SCL_HIGH;
MB85RC64_SDA_HIGH;
}
#ifdef SOFTWARE_I2C
/*
@ brief SDA引脚为输出模式
@ -76,8 +22,8 @@ void mb85rc64_gpio_init()
*/
static void mb85rc64_sda_output()
{
gpio_mode_set(GPIOB, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, GPIO_PIN_7);
gpio_output_options_set(GPIOB, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, GPIO_PIN_7);
gpio_mode_set(GPIOB, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, I2C_SDA_PIN);
gpio_output_options_set(GPIOB, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, I2C_SDA_PIN);
MB85RC64_SDA_HIGH;
}
@ -89,8 +35,8 @@ static void mb85rc64_sda_output()
*/
static void mb85rc64_sda_input()
{
gpio_mode_set(GPIOB, GPIO_MODE_INPUT, GPIO_PUPD_PULLUP, GPIO_PIN_7);
gpio_output_options_set(GPIOB, GPIO_PUPD_NONE, GPIO_OSPEED_50MHZ, GPIO_PIN_7);
gpio_mode_set(GPIOB, GPIO_MODE_INPUT, GPIO_PUPD_PULLUP, I2C_SDA_PIN);
gpio_output_options_set(GPIOB, GPIO_PUPD_NONE, GPIO_OSPEED_50MHZ, I2C_SDA_PIN);
}
/*
@ -247,116 +193,177 @@ static uint8_t mb85rc64_read_byte()
/*
@ brief
@ param addr:data:data_len
@ param addr:data:data_lenstatues
@ return
@ note 2022-05-27
*/
char mb85rc64_page_write(unsigned short int addr, unsigned char* data, int data_len)
bool mb85rc64_write_read(unsigned short int addr, unsigned char* data, int data_len, bool statues)
{
uint8_t addr_H = 0;
uint8_t addr_L = 0;
addr_H = (addr >> 8) & 0x00ff;
addr_L = addr & 0x00ff;
//启动信号
i2c_start();
//写地址,R/W位=0
mb85rc64_write_byte(MB85RC64_ADDRESS_WRITE);
//ack信号
mb85rc64_ack();
//写高8位地址
mb85rc64_write_byte(addr_H);
//ack信号
mb85rc64_ack();
//写低8位地址
mb85rc64_write_byte(addr_L);
//ack信号
mb85rc64_ack();
for(int i = 0; i < data_len; i++)
{
mb85rc64_write_byte(*data);
mb85rc64_ack();
data++;
}
//停止信号
i2c_stop();
return 1;
uint8_t addr_H = 0;
uint8_t addr_L = 0;
addr_H = (addr >> 8) & 0x00ff;
addr_L = addr & 0x00ff;
//启动信号
i2c_start();
//写地址,R/W位=0
// mb85rc64_write_byte(MB85RC64_ADDRESS_WRITE);
mb85rc64_write_byte(MB85RC64_ADDRESS << 1);
//ack信号
mb85rc64_ack();
//写高8位地址
mb85rc64_write_byte(addr_H);
//ack信号
mb85rc64_ack();
//写低8位地址
mb85rc64_write_byte(addr_L);
//ack信号
mb85rc64_ack();
if (statues == PAGE_WRITE)
{
for(int i = 0; i < data_len; i++)
{
mb85rc64_write_byte(*data);
mb85rc64_ack();
data++;
}
}
else if (statues == ADDR_READ)
{
//启动信号
i2c_start();
//写地址R/W为为1读数据
mb85rc64_write_byte((MB85RC64_ADDRESS << 1) + 1);
//ack信号
mb85rc64_ack();
for(int i = 0; i < data_len; i++)
{
//读数据
data[i] = mb85rc64_read_byte();
if(i == data_len - 1)
{
master_no_ack();
}
else
{
master_ack();
}
}
}
//停止信号
i2c_stop();
return 1;
}
#endif
#ifdef HARDWARE_I2C
/*
@ brief
@ param addr :data:, data_len:
@ return
@ note 2022-05-27 lqc
@ brief
@ param addr:data:data_lenstatues
@ return
@ note 2022-05-27
*/
char mb85rc64_add_read(unsigned short int addr, unsigned char *data, int data_len)
bool mb85rc64_write_read(unsigned short int addr, unsigned char* data, int data_len, bool statues)
{
uint8_t addr_H = 0;
uint8_t addr_L = 0;
addr_H = (addr >> 8) & 0x00ff;
addr_L = addr & 0x00ff;
//启动信号
i2c_start();
//写地址R/W位为0
mb85rc64_write_byte(MB85RC64_ADDRESS_WRITE);
//ack信号
mb85rc64_ack();
//写高8位地址
mb85rc64_write_byte(addr_H);
//ack信号
mb85rc64_ack();
//写低8位地址
mb85rc64_write_byte(addr_L);
//ack信号
mb85rc64_ack();
//启动信号
i2c_start();
//写地址R/W为为1读数据
mb85rc64_write_byte(MB85RC64_ADDRESS_READ);
//ack信号
mb85rc64_ack();
for(int i = 0; i < data_len; i++)
{
//读数据
data[i] = mb85rc64_read_byte();
if(i == data_len - 1)
uint8_t addr_HL[2];
addr_HL[0] = (addr >> 8) & 0x00ff;
addr_HL[1] = addr & 0x00ff;
/* 等待总线空闲 */
while(i2c_flag_get(I2C_PERIPH, I2C_FLAG_I2CBSY));
/* 发送起始条件 */
i2c_start_on_bus(I2C_PERIPH);
/* 等待起始条件已发送标志 */
while(!i2c_flag_get(I2C_PERIPH, I2C_FLAG_SBSEND));
/* 发送从机地址(写模式) */
i2c_master_addressing(I2C_PERIPH, MB85RC64_ADDRESS << 1, I2C_TRANSMITTER);
/* 等待地址已发送标志 */
while(!i2c_flag_get(I2C_PERIPH, I2C_FLAG_ADDSEND));
/* 清除地址发送标志 */
i2c_flag_clear(I2C_PERIPH, I2C_FLAG_ADDSEND);
for(int i = 0; i < 2; i++)
{
master_no_ack();
/* 等待发送数据缓冲区为空 */
while(!i2c_flag_get(I2C_PERIPH, I2C_FLAG_TBE));
/* 发送一个字节数据 */
i2c_data_transmit(I2C_PERIPH, addr_HL[i]);
}
else
{
master_ack();
}
}
//停止信号
i2c_stop();
return 1;
/* 等待数据传输完成 */
while(!i2c_flag_get(I2C_PERIPH, I2C_FLAG_TBE));
/* 清除数据传输完成标志 */
i2c_flag_clear(I2C_PERIPH, I2C_FLAG_TBE);
if (statues == PAGE_WRITE)
{
for(int i = 0; i < data_len; i++)
{
/* 等待发送数据缓冲区为空 */
while(!i2c_flag_get(I2C_PERIPH, I2C_FLAG_TBE));
/* 发送一个字节数据 */
i2c_data_transmit(I2C_PERIPH, data[i]);
}
}
else if (statues == ADDR_READ)
{
// /* 等待总线空闲 */
// while(i2c_flag_get(I2C_PERIPH, I2C_FLAG_I2CBSY));
/* 发送起始条件 */
i2c_start_on_bus(I2C_PERIPH);
/* 等待起始条件已发送标志 */
while(!i2c_flag_get(I2C_PERIPH, I2C_FLAG_SBSEND));
/* 发送从机地址(写模式) */
i2c_master_addressing(I2C_PERIPH, MB85RC64_ADDRESS << 1, I2C_RECEIVER);
/* 等待地址已发送标志 */
while(!i2c_flag_get(I2C_PERIPH, I2C_FLAG_ADDSEND));
/* 清除地址发送标志 */
i2c_flag_clear(I2C_PERIPH, I2C_FLAG_ADDSEND);
/* 5. 接收数据 */
if(data_len > 1)
{
/* 使能ACK多个字节接收时需要应答 */
i2c_ack_config(I2C_PERIPH, I2C_ACK_ENABLE);
for(int i = 0; i < data_len; i++)
{
if(i == (data_len - 1))
{
/* 最后一个字节前禁用ACK */
i2c_ack_config(I2C_PERIPH, I2C_ACK_DISABLE);
}
/* 等待RBNE标志接收缓冲区非空 */
while(!i2c_flag_get(I2C_PERIPH, I2C_FLAG_RBNE));
/* 读取数据 */
data[i] = i2c_data_receive(I2C_PERIPH);
}
}
else
{
/* 单字节接收直接禁用ACK */
i2c_ack_config(I2C_PERIPH, I2C_ACK_DISABLE);
/* 等待RBNE标志 */
while(!i2c_flag_get(I2C_PERIPH, I2C_FLAG_RBNE));
/* 读取数据 */
data[0] = i2c_data_receive(I2C_PERIPH);
}
}
/* 发送停止信号 */
i2c_stop_on_bus(I2C_PERIPH);
/* 等待停止信号完成 */
while(I2C_CTL0(I2C_PERIPH) & I2C_CTL0_STOP);
return 1;
}
void read_mb_id(uint8_t* buff)
{
i2c_start();
mb85rc64_write_byte(0xf8);
mb85rc64_ack();
mb85rc64_write_byte(MB85RC64_ADDRESS_WRITE);
mb85rc64_ack();
i2c_start();
mb85rc64_write_byte(0xf9);
mb85rc64_ack();
for(int i = 0; i < 3; i++)
{
//读数据
buff[i] = mb85rc64_read_byte();
if(i == 3 - 1)
{
master_no_ack();
}
else
{
master_ack();
}
}
i2c_stop();
}
#endif

View File

@ -14,23 +14,27 @@
#define __MB85RC64_H_
#include "gd32f4xx_gpio.h"
#include "drv_i2c.h"
#include "stdbool.h"
#include "delay.h"
#define MB85RC64_ADDRESS_WRITE 0xA0
#define MB85RC64_ADDRESS_READ 0xA1
#define MB85RC64_ADDRESS 0x50
#define MB85RC64_SCL_HIGH gpio_bit_set(GPIOB, GPIO_PIN_6)
#define MB85RC64_SCL_LOW gpio_bit_reset(GPIOB, GPIO_PIN_6)
#define PAGE_WRITE 1
#define ADDR_READ 0
#define MB85RC64_SDA_HIGH gpio_bit_set(GPIOB, GPIO_PIN_7)
#define MB85RC64_SDA_LOW gpio_bit_reset(GPIOB, GPIO_PIN_7)
#define MB85RC64_SDA_GET gpio_input_bit_get(GPIOB, GPIO_PIN_7)
//mb85rc64´æ´¢µØÖ·
#define MB85RC64_SAVE_ADDRESS_BEGIN 0x0000
#ifdef SOFTWARE_I2C
#define MB85RC64_SCL_HIGH I2C_SCL_HIGH
#define MB85RC64_SCL_LOW I2C_SCL_LOW
#define MB85RC64_SDA_HIGH I2C_SDA_HIGH
#define MB85RC64_SDA_LOW I2C_SDA_LOW
#define MB85RC64_SDA_GET I2C_SDA_GET
#endif
bool mb85rc64_write_read(unsigned short int addr, unsigned char* data, int data_len, bool statues);
void mb85rc64_gpio_init();
char mb85rc64_page_write(unsigned short int addr, unsigned char* data, int data_len);
char mb85rc64_add_read(unsigned short int addr, unsigned char *data, int data_len);
void mb85rc64_function_test();
void read_mb_id(uint8_t* buff);
#endif

View File

@ -0,0 +1,114 @@
#include "cfifo.h"
/*环形CFIFO初始化*/
void CfifoBuffInit(CfifoBuff* cfifoPointer)
{
//初始化相关信息
cfifoPointer->Head = 0;
cfifoPointer->Tail = 0;
cfifoPointer->Lenght = 0;
memset(cfifoPointer->BUFF,'\0',CFIFO_SIZE); //环形CFIFO缓存区初始化
}
/*环形CFIFO数据清除*/
void CfifoBuffClear(CfifoBuff* cfifoPointer)
{
//清除相关信息
cfifoPointer->Head = 0;
cfifoPointer->Tail = 0;
cfifoPointer->Lenght = 0;
memset(cfifoPointer->BUFF,'\0',CFIFO_SIZE); //环形CFIFO缓存区清除
}
/*环形CFIFO数据写入*/
/*
*:
* Cfifo_pointerCFIFO结构体
* User_buff
* num
*
*FIFO缓存区中的数据长度
*
*User_buff中的数据写入到环形CFIFO缓存区
*
*/
int16_t CfifoBuffWrite(CfifoBuff* cfifoPointer, char* userBuff, int32_t num)
{
int16_t i , writeNum;
if(cfifoPointer->Lenght >= CFIFO_SIZE) //判断缓存区是否已满
{
writeNum = -1;
return writeNum; //数据溢出
}
if(cfifoPointer->Lenght + num < CFIFO_SIZE) //判断写入的数据长度是否超出当前可写入的最大值
{
writeNum = num;
}
else
{
writeNum = CFIFO_SIZE - cfifoPointer->Lenght;
}
for(i=0; i<writeNum; i++)
{
cfifoPointer->BUFF[cfifoPointer->Tail] = *(userBuff+i);
cfifoPointer->Tail = (cfifoPointer->Tail+1) % CFIFO_SIZE;//防止越界非法访问
}
cfifoPointer->Lenght += writeNum;
return writeNum; //返回正确写入的数据长度
}
/*环形CFIFO读取*/
/*
*:
* Cfifo_pointerCFIFO结构体
* User_buff
* num
*
*User_buff的数据长度
*
*CFIFO缓存区的数据读取到User_buff
*
*/
int16_t CfifoBuffRead(CfifoBuff* cfifoPointer, char* userBuff, int32_t num)
{
int16_t i , readNum;
if(cfifoPointer->Lenght == 0) //判断非空
{
readNum = -1;
return readNum; //没有数据
}
if( cfifoPointer->Lenght - num >= 0) //判断读取的数据长度是否超出当前可读取的最大值
{
readNum = num;
}
else
{
readNum = cfifoPointer->Lenght;
}
for(i=0; i<readNum; i++)
{
*(userBuff+i) = cfifoPointer->BUFF[cfifoPointer->Head];
cfifoPointer->Head = (cfifoPointer->Head+1) % CFIFO_SIZE;//防止越界非法访问
}
cfifoPointer->Lenght -= readNum;
return readNum; //返回正确写入的数据长度
}

View File

@ -0,0 +1,43 @@
#ifndef _CFIFO_H_
#define _CFIFO_H_
/*
*************************************************************************
*
*************************************************************************
*/
#include <string.h>
#include <stdio.h>
#include "stdint.h"
/*
*************************************************************************
*
*************************************************************************
*/
#define CFIFO_SIZE 1024//环形队列CFIFO大小
/*环形CFIFO结构体*/
typedef struct
{
uint16_t Head; //环形CFIFO队列头
uint16_t Tail; //环形CFIFO队列尾
int32_t Lenght; //环形CFIFO数据长度
uint8_t BUFF[CFIFO_SIZE]; //环形CFIFO缓存区
}CfifoBuff;
/*
*************************************************************************
*
*************************************************************************
*/
void CfifoBuffInit(CfifoBuff* cfifoPointer); //CFIFO初始化
void CfifoBuffClear(CfifoBuff* cfifoPointer); //CFIFO数据清除
int16_t CfifoBuffWrite(CfifoBuff* cfifoPointer, char* userBuff, int32_t num); //CFIFO数据写人
int16_t CfifoBuffRead(CfifoBuff* cfifoPointer, char* userBuff, int32_t num); //CFIFO数据读出
#endif /* _CFIFO_H_ */

View File

@ -0,0 +1,66 @@
#include "stdint.h"
static const uint8_t aucCRCHi[] = {
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41,
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40,
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41,
0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41,
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41,
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40,
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40,
0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40,
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41,
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40,
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41,
0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41,
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41,
0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41,
0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41,
0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41,
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41,
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40,
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41,
0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41,
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41,
0x00, 0xC1, 0x81, 0x40
};
static const uint8_t aucCRCLo[] = {
0x00, 0xC0, 0xC1, 0x01, 0xC3, 0x03, 0x02, 0xC2, 0xC6, 0x06, 0x07, 0xC7,
0x05, 0xC5, 0xC4, 0x04, 0xCC, 0x0C, 0x0D, 0xCD, 0x0F, 0xCF, 0xCE, 0x0E,
0x0A, 0xCA, 0xCB, 0x0B, 0xC9, 0x09, 0x08, 0xC8, 0xD8, 0x18, 0x19, 0xD9,
0x1B, 0xDB, 0xDA, 0x1A, 0x1E, 0xDE, 0xDF, 0x1F, 0xDD, 0x1D, 0x1C, 0xDC,
0x14, 0xD4, 0xD5, 0x15, 0xD7, 0x17, 0x16, 0xD6, 0xD2, 0x12, 0x13, 0xD3,
0x11, 0xD1, 0xD0, 0x10, 0xF0, 0x30, 0x31, 0xF1, 0x33, 0xF3, 0xF2, 0x32,
0x36, 0xF6, 0xF7, 0x37, 0xF5, 0x35, 0x34, 0xF4, 0x3C, 0xFC, 0xFD, 0x3D,
0xFF, 0x3F, 0x3E, 0xFE, 0xFA, 0x3A, 0x3B, 0xFB, 0x39, 0xF9, 0xF8, 0x38,
0x28, 0xE8, 0xE9, 0x29, 0xEB, 0x2B, 0x2A, 0xEA, 0xEE, 0x2E, 0x2F, 0xEF,
0x2D, 0xED, 0xEC, 0x2C, 0xE4, 0x24, 0x25, 0xE5, 0x27, 0xE7, 0xE6, 0x26,
0x22, 0xE2, 0xE3, 0x23, 0xE1, 0x21, 0x20, 0xE0, 0xA0, 0x60, 0x61, 0xA1,
0x63, 0xA3, 0xA2, 0x62, 0x66, 0xA6, 0xA7, 0x67, 0xA5, 0x65, 0x64, 0xA4,
0x6C, 0xAC, 0xAD, 0x6D, 0xAF, 0x6F, 0x6E, 0xAE, 0xAA, 0x6A, 0x6B, 0xAB,
0x69, 0xA9, 0xA8, 0x68, 0x78, 0xB8, 0xB9, 0x79, 0xBB, 0x7B, 0x7A, 0xBA,
0xBE, 0x7E, 0x7F, 0xBF, 0x7D, 0xBD, 0xBC, 0x7C, 0xB4, 0x74, 0x75, 0xB5,
0x77, 0xB7, 0xB6, 0x76, 0x72, 0xB2, 0xB3, 0x73, 0xB1, 0x71, 0x70, 0xB0,
0x50, 0x90, 0x91, 0x51, 0x93, 0x53, 0x52, 0x92, 0x96, 0x56, 0x57, 0x97,
0x55, 0x95, 0x94, 0x54, 0x9C, 0x5C, 0x5D, 0x9D, 0x5F, 0x9F, 0x9E, 0x5E,
0x5A, 0x9A, 0x9B, 0x5B, 0x99, 0x59, 0x58, 0x98, 0x88, 0x48, 0x49, 0x89,
0x4B, 0x8B, 0x8A, 0x4A, 0x4E, 0x8E, 0x8F, 0x4F, 0x8D, 0x4D, 0x4C, 0x8C,
0x44, 0x84, 0x85, 0x45, 0x87, 0x47, 0x46, 0x86, 0x82, 0x42, 0x43, 0x83,
0x41, 0x81, 0x80, 0x40
};
uint16_t ModbusCRC16(uint8_t *pucFrame, uint16_t usLen)
{
uint8_t ucCRCHi = 0xFF;
uint8_t ucCRCLo = 0xFF;
int iIndex;
while(usLen--)
{
iIndex = ucCRCLo ^ *(pucFrame++);
ucCRCLo = (uint8_t)(ucCRCHi ^ aucCRCHi[iIndex]);
ucCRCHi = aucCRCLo[iIndex];
}
return (uint16_t)(ucCRCHi << 8 | ucCRCLo);
}

View File

@ -0,0 +1,7 @@
#ifndef _MODBUS_CRC_H_
#define _MODBUS_CRC_H_
uint16_t ModbusCRC16(uint8_t *pucFrame, uint16_t usLen);
#endif

View File

@ -0,0 +1,634 @@
#include "motorCommu.h"
/*
********************************************************************************************************
*
********************************************************************************************************
*/
typedef struct
{
uint32_t gpio; //引脚端口号
rcu_periph_enum rcuGpio; //GPIO时钟
uint32_t uartNo; //串口号
rcu_periph_enum rcuUart; //串口时钟
uint32_t modePin; //rs485收发模式切换引脚
uint32_t txPin; //串口发送引脚
uint32_t rxPin; //串口接收引脚
IRQn_Type uartIrq; //串口中断号
}MotorCommuHwInfo_t;//电机与外部通讯的串口
static MotorCommuHwInfo_t g_motorCommuBuff[] =
{
//水平电机串口2
{
.gpio = GPIOD,
.rcuGpio = RCU_GPIOD,
.uartNo = USART2,
.rcuUart = RCU_USART2,
.modePin = GPIO_PIN_10,
.txPin = GPIO_PIN_8,
.rxPin = GPIO_PIN_9,
.uartIrq = USART2_IRQn,
},
//垂直电机串口5
{
.gpio = GPIOC,
.rcuGpio = RCU_GPIOC,
.uartNo = USART5,
.rcuUart = RCU_USART5,
.modePin = GPIO_PIN_8,
.txPin = GPIO_PIN_6,
.rxPin = GPIO_PIN_7,
.uartIrq = USART5_IRQn,
},
};
#define MOTOR_NUM ( sizeof(g_motorCommuBuff) / sizeof(g_motorCommuBuff[0]) )
/*
********************************************************************************************************
* DMA驱动初始化结构体
********************************************************************************************************
*/
typedef struct
{
uint32_t dmaNo; //dma号dma0或dma1
rcu_periph_enum rcuDma; //dma时钟
dma_channel_enum dmaTxch; //dma发送通道号
dma_channel_enum dmaRxch; //dma接收通道号
dma_subperipheral_enum dmaPeriph; //dma外设通道号
uint32_t periphAddr; //dma外设地址
IRQn_Type dmaTxIrq; //dma发送通道中断号
IRQn_Type dmaRxIrq; //dma接收通道中断号
uint32_t dmaTxPri; //dma发送优先级
uint32_t dmaRxPri; //dma接收优先级
}MotorCommuDmaHwInfo_t;
static MotorCommuDmaHwInfo_t g_MotorDmaBuff[] =
{
//水平电机串口2
{
.dmaNo = DMA0,
.rcuDma = RCU_DMA0,
.dmaTxch = DMA_CH3,
.dmaRxch = DMA_CH1,
.dmaPeriph = DMA_SUBPERI4,
.periphAddr = USART2 + 0x04,
.dmaTxIrq = DMA0_Channel3_IRQn,
.dmaRxIrq = DMA0_Channel1_IRQn,
.dmaTxPri = 2,//0,1,2,3对于优先级低、中、高、特高
.dmaRxPri = 2,
},
//垂直电机串口5
{
.dmaNo = DMA1,
.rcuDma = RCU_DMA1,
.dmaTxch = DMA_CH7,
.dmaRxch = DMA_CH1,
.dmaPeriph = DMA_SUBPERI5,
.periphAddr = USART5 + 0x04,
.dmaTxIrq = DMA1_Channel7_IRQn,
.dmaRxIrq = DMA1_Channel1_IRQn,
.dmaTxPri = 2,//0,1,2,3对于优先级低、中、高、特高
.dmaRxPri = 2,
},
};
/*
********************************************************************************************************
*
********************************************************************************************************
*/
/* dma发送与接收缓冲区 */
static uint8_t g_horiDmaTxBuff[DMA_BUFF_SIZE] = {0};//水平电机DMA发送缓存区
static uint8_t g_horiDmaRxBuff[DMA_BUFF_SIZE] = {0};//水平电机DMA接受缓存区
static uint8_t g_vertDmaTxBuff[DMA_BUFF_SIZE] = {0};//垂直电机DMA发送缓存区
static uint8_t g_vertDmaRxBuff[DMA_BUFF_SIZE] = {0};//垂直电机DMA接受缓存区
/* 处理串口通讯与数据缓冲的数据结构 */
static CommuInfo_t g_horiCommuDeal; //水平电机
static CommuInfo_t g_vertCommuDeal; //垂直电机
typedef struct
{
CommuInfo_t* pCommuInfo; //串口通讯与数据缓冲相关的数据结构
uint8_t* dmaTxBuff; //dma发送缓存区指针
uint8_t* dmaRxBuff; //dma接受缓存区指针
}CommuHwInfo_t;//方便缓冲区初始化的结构体
static CommuHwInfo_t g_commuInfoBuff[] =
{
//水平电机
{
.pCommuInfo = &g_horiCommuDeal,
.dmaTxBuff = g_horiDmaTxBuff,
.dmaRxBuff = g_horiDmaRxBuff,
},
//垂直电机串口5
{
.pCommuInfo = &g_vertCommuDeal,
.dmaTxBuff = g_vertDmaTxBuff,
.dmaRxBuff = g_vertDmaRxBuff,
},
};
/*
********************************************************************************************************
*
********************************************************************************************************
*/
static void GpioCofig(void)
{
for(uint8_t i = 0; i < MOTOR_NUM; i++)//i==0初始化水平电机IOi==1初始化垂直电机io
{
/*GPIO时钟初始化*/
rcu_periph_clock_enable(g_motorCommuBuff[i].rcuGpio);
/*io复用为串口uart*/
if ( i == H_MOTOR )
{
gpio_af_set(g_motorCommuBuff[i].gpio, GPIO_AF_7, g_motorCommuBuff[i].txPin);
gpio_af_set(g_motorCommuBuff[i].gpio, GPIO_AF_7, g_motorCommuBuff[i].rxPin);
}
else
{
gpio_af_set(g_motorCommuBuff[i].gpio, GPIO_AF_8, g_motorCommuBuff[i].txPin);
gpio_af_set(g_motorCommuBuff[i].gpio, GPIO_AF_8, g_motorCommuBuff[i].rxPin);
}
/*tx引脚配置*/
gpio_mode_set(g_motorCommuBuff[i].gpio, GPIO_MODE_AF, GPIO_PUPD_NONE, g_motorCommuBuff[i].txPin);
gpio_output_options_set(g_motorCommuBuff[i].gpio, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, g_motorCommuBuff[i].txPin);
/*rx引脚配置*/
gpio_mode_set(g_motorCommuBuff[i].gpio, GPIO_MODE_AF, GPIO_PUPD_NONE, g_motorCommuBuff[i].rxPin);
gpio_output_options_set(g_motorCommuBuff[i].gpio, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, g_motorCommuBuff[i].rxPin);
/*rs485收发模式切换引脚配置*/
gpio_mode_set(g_motorCommuBuff[i].gpio, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, g_motorCommuBuff[i].modePin);
gpio_output_options_set(g_motorCommuBuff[i].gpio, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, g_motorCommuBuff[i].modePin);
}
}
static void UartCofig(uint32_t baud)
{
for(uint8_t i = 0; i < MOTOR_NUM; i++)//i==0初始化水平电机IOi==1初始化垂直电机io
{
/*UART时钟初始化*/
rcu_periph_clock_enable(g_motorCommuBuff[i].rcuUart);
/*串口复位*/
usart_deinit (g_motorCommuBuff[i].uartNo);
/*串口配置*/
usart_word_length_set(g_motorCommuBuff[i].uartNo, USART_WL_8BIT);
usart_parity_config(g_motorCommuBuff[i].uartNo, USART_PM_NONE);
usart_stop_bit_set(g_motorCommuBuff[i].uartNo, USART_STB_1BIT);
usart_baudrate_set(g_motorCommuBuff[i].uartNo, baud);
usart_hardware_flow_rts_config(g_motorCommuBuff[i].uartNo, USART_RTS_DISABLE);
usart_hardware_flow_cts_config(g_motorCommuBuff[i].uartNo, USART_CTS_DISABLE);
usart_transmit_config(g_motorCommuBuff[i].uartNo, USART_TRANSMIT_ENABLE);
usart_receive_config(g_motorCommuBuff[i].uartNo, USART_RECEIVE_ENABLE);
usart_dma_transmit_config(g_motorCommuBuff[i].uartNo, USART_DENT_ENABLE);
usart_dma_receive_config(g_motorCommuBuff[i].uartNo, USART_DENR_ENABLE);
/*中断配置*/
usart_interrupt_enable(g_motorCommuBuff[i].uartNo, USART_INT_IDLE);
nvic_irq_enable(g_motorCommuBuff[i].uartIrq, 3, 0);
usart_enable(g_motorCommuBuff[i].uartNo);
}
}
static void DmaCofig(void)
{
for(uint8_t i = 0; i < MOTOR_NUM; i++)//i==0初始化水平电机IOi==1初始化垂直电机io
{
dma_single_data_parameter_struct dmaStruct;
rcu_periph_clock_enable(g_MotorDmaBuff[i].rcuDma);
/*--------------------------------dma发送数据完全传输中断初始化---------------------------------*/
//dma配置
dma_deinit(g_MotorDmaBuff[i].dmaNo, g_MotorDmaBuff[i].dmaTxch);
dmaStruct.direction = DMA_MEMORY_TO_PERIPH;
dmaStruct.memory0_addr = (uint32_t)0;
dmaStruct.memory_inc = DMA_MEMORY_INCREASE_ENABLE;
dmaStruct.periph_memory_width = DMA_PERIPH_WIDTH_8BIT;
dmaStruct.periph_addr = g_MotorDmaBuff[i].periphAddr;
dmaStruct.periph_inc = DMA_PERIPH_INCREASE_DISABLE;
dmaStruct.number = 0;
dmaStruct.priority = CHCTL_PRIO(g_MotorDmaBuff[i].dmaTxPri);
dma_single_data_mode_init(g_MotorDmaBuff[i].dmaNo, g_MotorDmaBuff[i].dmaTxch, &dmaStruct);
dma_circulation_disable(g_MotorDmaBuff[i].dmaNo, g_MotorDmaBuff[i].dmaTxch);
dma_channel_subperipheral_select(g_MotorDmaBuff[i].dmaNo, g_MotorDmaBuff[i].dmaTxch, g_MotorDmaBuff[i].dmaPeriph);
//dma中断配置
nvic_irq_enable(g_MotorDmaBuff[i].dmaTxIrq, 4, 3);
dma_interrupt_enable(g_MotorDmaBuff[i].dmaNo, g_MotorDmaBuff[i].dmaTxch, DMA_CHXCTL_FTFIE);//dma发送完成中断
/*--------------------------------dma接收配合串口空闲中断初始化---------------------------------*/
//dma配置
dma_deinit(g_MotorDmaBuff[i].dmaNo, g_MotorDmaBuff[i].dmaRxch);
dmaStruct.direction = DMA_PERIPH_TO_MEMORY;
dmaStruct.memory0_addr = (uint32_t)(g_commuInfoBuff[i].pCommuInfo->pDmaRsvBuff);
dmaStruct.memory_inc = DMA_MEMORY_INCREASE_ENABLE;
dmaStruct.number = DMA_BUFF_SIZE;
dmaStruct.periph_addr = g_MotorDmaBuff[i].periphAddr;
dmaStruct.periph_inc = DMA_PERIPH_INCREASE_DISABLE;
dmaStruct.periph_memory_width = DMA_PERIPH_WIDTH_8BIT;
dmaStruct.priority = CHCTL_PRIO(g_MotorDmaBuff[i].dmaRxPri);;
dma_memory_width_config(g_MotorDmaBuff[i].dmaNo, g_MotorDmaBuff[i].dmaRxch, DMA_MEMORY_WIDTH_8BIT);
dma_periph_width_config(g_MotorDmaBuff[i].dmaNo, g_MotorDmaBuff[i].dmaRxch, DMA_PERIPH_WIDTH_8BIT);
dma_single_data_mode_init(g_MotorDmaBuff[i].dmaNo, g_MotorDmaBuff[i].dmaRxch, &dmaStruct);
dma_circulation_enable(g_MotorDmaBuff[i].dmaNo, g_MotorDmaBuff[i].dmaRxch);//循环模式
dma_channel_subperipheral_select(g_MotorDmaBuff[i].dmaNo, g_MotorDmaBuff[i].dmaRxch, g_MotorDmaBuff[i].dmaPeriph);
//中断配置
nvic_irq_enable(g_MotorDmaBuff[i].dmaRxIrq, 4, 2);
dma_interrupt_enable(g_MotorDmaBuff[i].dmaNo, g_MotorDmaBuff[i].dmaRxch, DMA_CHXCTL_FTFIE);
dma_channel_enable(g_MotorDmaBuff[i].dmaNo, g_MotorDmaBuff[i].dmaRxch);
}
}
/*
********************************************************************************************************
*
********************************************************************************************************
*/
/*!
\brief DMA的空间大小DMA偏移量
\param[in] none
\param[out] none
\retval none
*/
static void CommuStructInit()
{
for(uint8_t i = 0; i < MOTOR_NUM; i++)//i==0初始化水平电机IOi==1初始化垂直电机io
{
/*为属性的参数附初值*/
CommuInfo_t *pCommuDeal = g_commuInfoBuff[i].pCommuInfo;
pCommuDeal->dmaOffset = 0;
pCommuDeal->dmaTranFlag = DMA_TRANS_IDLE;
pCommuDeal->dmaSize = DMA_BUFF_SIZE;
pCommuDeal->pDmaRsvBuff = g_commuInfoBuff[i].dmaRxBuff;
pCommuDeal->pDmaTraBuff = g_commuInfoBuff[i].dmaTxBuff;
CfifoBuffInit(&pCommuDeal->dataRsvCfifo); //用于数据接受
CfifoBuffInit(&pCommuDeal->dataTraCfifo); //用于数据发送
}
}
/*!
\brief DMA的数据发送
\param[in] devNoH_MOTORV_MOTOR
\param[in] buffer
\param[in] len
\param[out] none
\retval none
*/
static void CommuDmaTra(uint8_t devNo, uint8_t *buffer,uint16_t len)
{
dma_channel_disable(g_MotorDmaBuff[devNo].dmaNo, g_MotorDmaBuff[devNo].dmaTxch);
dma_memory_address_config(g_MotorDmaBuff[devNo].dmaNo, g_MotorDmaBuff[devNo].dmaTxch, DMA_MEMORY_0, (uint32_t)buffer);
dma_transfer_number_config(g_MotorDmaBuff[devNo].dmaNo, g_MotorDmaBuff[devNo].dmaTxch, len);
/*清除DMA发送完成的标志*/
dma_flag_clear(g_MotorDmaBuff[devNo].dmaNo, g_MotorDmaBuff[devNo].dmaTxch, DMA_FLAG_FTF);
usart_flag_clear(g_motorCommuBuff[devNo].uartNo, USART_FLAG_TC);
dma_channel_enable(g_MotorDmaBuff[devNo].dmaNo, g_MotorDmaBuff[devNo].dmaTxch);
}
/*
********************************************************************************************************
*
********************************************************************************************************
*/
/*!
\brief this function handles DMA0_Channel3_IRQHandler interrupt
\param[in] none
\param[out] none
\retval none
*/
void DMA0_Channel3_IRQHandler(void)
{
/*
*
* CNT次数后
*/
int32_t TransNum = 0;//从&pCommuDeal->dataTraCfifo.BUFF[]中获取多少数据
if(dma_interrupt_flag_get(g_MotorDmaBuff[H_MOTOR].dmaNo, g_MotorDmaBuff[H_MOTOR].dmaTxch, DMA_INT_FLAG_FTF))
{
dma_interrupt_flag_clear(g_MotorDmaBuff[H_MOTOR].dmaNo, g_MotorDmaBuff[H_MOTOR].dmaTxch, DMA_INT_FLAG_FTF);
CommuInfo_t *pCommuDeal = g_commuInfoBuff[H_MOTOR].pCommuInfo;
/*从发送循环缓冲区中获取数据*/
TransNum = CfifoBuffRead(&pCommuDeal->dataTraCfifo,(char *)(pCommuDeal->pDmaTraBuff),pCommuDeal->dmaSize);
if(TransNum > 0)
{
CommuDmaTra(H_MOTOR, pCommuDeal->pDmaTraBuff, TransNum);
}
else
{
while(usart_flag_get(g_motorCommuBuff[H_MOTOR].uartNo, USART_FLAG_TC) == RESET); // 等待串口发送完成
H_COMMU_RS485_RX; //485切换为接收
pCommuDeal->dmaTranFlag = DMA_TRANS_IDLE;
}
}
}
/**
***********************************************************
* @brief
* @param
* @return
***********************************************************
*/
static uint16_t g_hFrameRcvNum = 0;
void USART2_IRQHandler(void)
{
/* 串口的接收空闲中断方式进行了数据缓存。*/
int32_t RecvNum = 0;//dma缓冲区收到多少数据
int32_t WriteNum = 0;//向数据循环接收区写入的数据数正常WriteNum==RecvNum
int32_t DmaIdleNum = 0;//dmasize减已经传输的数据就是DmaIdleNum
if(RESET != usart_interrupt_flag_get(g_motorCommuBuff[H_MOTOR].uartNo, USART_INT_FLAG_IDLE))
{
/* clear IDLE flag */
usart_interrupt_flag_clear(g_motorCommuBuff[H_MOTOR].uartNo, USART_INT_FLAG_IDLE); //第一步读取stat0寄存器清除IDLE标志位
usart_data_receive(g_motorCommuBuff[H_MOTOR].uartNo); //第二步读取数据寄存器清除IDLE标志位
g_hFrameRcvNum++;
CommuInfo_t *pCommuDeal = g_commuInfoBuff[H_MOTOR].pCommuInfo;
/*计算在DMA缓冲区需要获取的数据长度*/
DmaIdleNum = dma_transfer_number_get(g_MotorDmaBuff[H_MOTOR].dmaNo, g_MotorDmaBuff[H_MOTOR].dmaRxch);//获取的是还有多少个没传输,而不是已经传输了多少
RecvNum = pCommuDeal->dmaSize - DmaIdleNum - pCommuDeal->dmaOffset;
/*将获取到的数据放到数据接收缓冲区中*/
WriteNum = CfifoBuffWrite(&pCommuDeal->dataRsvCfifo,(char *)(pCommuDeal->pDmaRsvBuff + pCommuDeal->dmaOffset), RecvNum);
if(WriteNum != RecvNum)
{
printf("Uart ReadFifo is not enough\r\n");
}
/*计算获取数据位置的偏移量*/
pCommuDeal->dmaOffset += RecvNum;
}
}
void DMA0_Channel1_IRQHandler(void)
{
int32_t RecvNum = 0;
int32_t WriteNum = 0;
/*
* 1DMA的偏移量
* 11 pUartAttr->DamOffset置为0;
* 2DMA为循环方式进行数据搬运的Cnt后
* 3;
* 4DMA为正常模式,DMA会自动disable掉
*/
if(dma_interrupt_flag_get(g_MotorDmaBuff[H_MOTOR].dmaNo, g_MotorDmaBuff[H_MOTOR].dmaRxch, DMA_INT_FLAG_FTF))
{
dma_interrupt_flag_clear(g_MotorDmaBuff[H_MOTOR].dmaNo, g_MotorDmaBuff[H_MOTOR].dmaRxch, DMA_INT_FLAG_FTF);
CommuInfo_t *pCommuDeal = g_commuInfoBuff[H_MOTOR].pCommuInfo;
/* 将dma缓冲马上传输完成剩余最后一截子的数据拷贝到缓冲区中在进行偏移量的复位 */
RecvNum = pCommuDeal->dmaSize - pCommuDeal->dmaOffset;
/*将获取到的数据放到数据接收缓冲区中*/
WriteNum = CfifoBuffWrite(&pCommuDeal->dataRsvCfifo,(char *)(pCommuDeal->pDmaRsvBuff + pCommuDeal->dmaOffset), RecvNum);
if(WriteNum != RecvNum)
{
/*add deal here*/
}
/*复位DMA偏移量*/
pCommuDeal->dmaOffset = 0;
}
}
/*
********************************************************************************************************
*
********************************************************************************************************
*/
/*!
\brief this function handles DMA0_Channel3_IRQHandler interrupt
\param[in] none
\param[out] none
\retval none
*/
void DMA1_Channel7_IRQHandler(void)
{
/*
*
* CNT次数后
*/
int32_t TransNum = 0;//从&pCommuDeal->dataTraCfifo.BUFF[]中获取多少数据
if(dma_interrupt_flag_get(g_MotorDmaBuff[V_MOTOR].dmaNo, g_MotorDmaBuff[V_MOTOR].dmaTxch, DMA_INT_FLAG_FTF))
{
dma_interrupt_flag_clear(g_MotorDmaBuff[V_MOTOR].dmaNo, g_MotorDmaBuff[V_MOTOR].dmaTxch, DMA_INT_FLAG_FTF);
CommuInfo_t *pCommuDeal = g_commuInfoBuff[V_MOTOR].pCommuInfo;
/*从发送循环缓冲区中获取数据*/
TransNum = CfifoBuffRead(&pCommuDeal->dataTraCfifo,(char *)(pCommuDeal->pDmaTraBuff),pCommuDeal->dmaSize);
if(TransNum > 0)
{
CommuDmaTra(V_MOTOR, pCommuDeal->pDmaTraBuff, TransNum);
}
else
{
while(usart_flag_get(g_motorCommuBuff[V_MOTOR].uartNo, USART_FLAG_TC) == RESET); // 等待串口发送完成
V_COMMU_RS485_RX; //485切换为接收
pCommuDeal->dmaTranFlag = DMA_TRANS_IDLE;
}
// pCommuDeal->dmaTranFlag = DMA_TRANS_IDLE;
// V_COMMU_RS485_RX; //485切换为接收
}
}
/**
***********************************************************
* @brief
* @param
* @return
***********************************************************
*/
static uint16_t g_vFrameRcvNum = 0;
void USART5_IRQHandler(void)
{
/* 串口的接收空闲中断方式进行了数据缓存。*/
int32_t RecvNum = 0;//dma缓冲区收到多少数据
int32_t WriteNum = 0;//向数据循环接收区写入的数据数正常WriteNum==RecvNum
int32_t DmaIdleNum = 0;//dmasize减已经传输的数据就是DmaIdleNum
if(RESET != usart_interrupt_flag_get(g_motorCommuBuff[V_MOTOR].uartNo, USART_INT_FLAG_IDLE))
{
/* clear IDLE flag */
usart_interrupt_flag_clear(g_motorCommuBuff[V_MOTOR].uartNo, USART_INT_FLAG_IDLE); //第一步读取stat0寄存器清除IDLE标志位
usart_data_receive(g_motorCommuBuff[V_MOTOR].uartNo); //第二步读取数据寄存器清除IDLE标志位
g_vFrameRcvNum++;
CommuInfo_t *pCommuDeal = g_commuInfoBuff[V_MOTOR].pCommuInfo;
/*计算在DMA缓冲区需要获取的数据长度*/
DmaIdleNum = dma_transfer_number_get(g_MotorDmaBuff[V_MOTOR].dmaNo, g_MotorDmaBuff[V_MOTOR].dmaRxch);//获取的是还有多少个没传输,而不是已经传输了多少
RecvNum = pCommuDeal->dmaSize - DmaIdleNum - pCommuDeal->dmaOffset;
/*将获取到的数据放到数据接收缓冲区中*/
WriteNum = CfifoBuffWrite(&pCommuDeal->dataRsvCfifo,(char *)(pCommuDeal->pDmaRsvBuff + pCommuDeal->dmaOffset), RecvNum);
if(WriteNum != RecvNum)
{
printf("Uart ReadFifo is not enough\r\n");
}
/*计算获取数据位置的偏移量*/
pCommuDeal->dmaOffset += RecvNum;
}
}
// uint8_t rx_OK = 0;
void DMA1_Channel1_IRQHandler(void)
{
int32_t RecvNum = 0;
int32_t WriteNum = 0;
/*
* 1DMA的偏移量
* 11 pUartAttr->DamOffset置为0;
* 2DMA为循环方式进行数据搬运的Cnt后
* 3;
* 4DMA为正常模式,DMA会自动disable掉
*/
if(dma_interrupt_flag_get(g_MotorDmaBuff[V_MOTOR].dmaNo, g_MotorDmaBuff[V_MOTOR].dmaRxch, DMA_INT_FLAG_FTF))
{
dma_interrupt_flag_clear(g_MotorDmaBuff[V_MOTOR].dmaNo, g_MotorDmaBuff[V_MOTOR].dmaRxch, DMA_INT_FLAG_FTF);
// rx_OK++;
CommuInfo_t *pCommuDeal = g_commuInfoBuff[V_MOTOR].pCommuInfo;
/* 将dma缓冲马上传输完成剩余最后一截子的数据拷贝到缓冲区中在进行偏移量的复位 */
RecvNum = pCommuDeal->dmaSize - pCommuDeal->dmaOffset;
/*将获取到的数据放到数据接收缓冲区中*/
WriteNum = CfifoBuffWrite(&pCommuDeal->dataRsvCfifo,(char *)(pCommuDeal->pDmaRsvBuff + pCommuDeal->dmaOffset), RecvNum);
if(WriteNum != RecvNum)
{
/*add deal here*/
}
/*复位DMA偏移量*/
pCommuDeal->dmaOffset = 0;
}
}
/*
********************************************************************************************************
* API接口函数
********************************************************************************************************
*/
/**
* @brief
* @param
* @return
*/
void CommuDrvInit(void)
{
CommuStructInit();//先初始化这个缓冲区数据结构体,否则硬件配置得不到地址
GpioCofig();
UartCofig(57600);
DmaCofig();
}
/**
* @brief
1
* @param motorNoH_MOTORV_MOTOR
* @param buffer
* @param len(DMA_BUFF_SIZE)
* @return
*/
int32_t CommuTransData(uint8_t motorNo, uint8_t* buffer, int32_t len)
{
int32_t TransNum = 0;
int32_t TransLen = 0;
// 使用数组为每个电机分配独立的计数器
static int32_t s_addUpDataNum[MOTOR_NUM] = {0};
if( motorNo == H_MOTOR )
{
H_COMMU_RS485_TX;
}
else
{
V_COMMU_RS485_TX;
}
CommuInfo_t *pCommuDeal = g_commuInfoBuff[motorNo].pCommuInfo;
/*将要发送的数据写入循环缓冲区*/
TransNum = CfifoBuffWrite(&pCommuDeal->dataTraCfifo, (char *) buffer, len);
s_addUpDataNum[motorNo] += len; // 使用对应电机的计数器
/*如果DMA未在发送中触发发送*/
if(pCommuDeal->dmaTranFlag == DMA_TRANS_IDLE)
{
TransLen = CfifoBuffRead(&pCommuDeal->dataTraCfifo,(char *)(pCommuDeal->pDmaTraBuff), s_addUpDataNum[motorNo]);
s_addUpDataNum[motorNo] = 0; // 清零对应电机的计数器
if(TransLen > 0)
{
pCommuDeal->dmaTranFlag = DMA_TRANS_BUSY;
CommuDmaTra(motorNo, pCommuDeal->pDmaTraBuff, TransLen);
}
}
return TransNum;
}
/**
* @brief
* @param motorNoH_MOTORV_MOTOR
* @param userBuff
* @param len
* @return none
*/
void CommuRsvData(uint8_t motorNo, uint8_t* userBuff, uint32_t len)
{
// if ( motorNo == H_MOTOR )
// {
// H_COMMU_RS485_RX;
// }
// else
// {
// V_COMMU_RS485_RX;
// }
CommuInfo_t *pCommuDeal = g_commuInfoBuff[motorNo].pCommuInfo;
CfifoBuffRead(&pCommuDeal->dataRsvCfifo, (char*)userBuff, len);
}
/**
* @brief 485422,
* @param motorNoH_MOTORV_MOTOR
* @return rs485或rs422接收到的包数量
*/
uint16_t GetRsvFrameNum(uint8_t motorNo)
{
if (motorNo == H_MOTOR)
{
return g_hFrameRcvNum;
}
return g_vFrameRcvNum;
}
/**
* @brief 485422,
1
* @param motorNoH_MOTORV_MOTOR
* @return null
*/
void DecRsvFrameNum(uint8_t motorNo)
{
if (motorNo == H_MOTOR && g_hFrameRcvNum > 0)
{
g_hFrameRcvNum--;
return;
}
if (motorNo == V_MOTOR && g_vFrameRcvNum > 0)
{
g_vFrameRcvNum--;
return;
}
}
///*用于结构体数组赋值,方便外部使用此结构体数组*/
//CommuHwInfo_t GetMotorCommuBuffStr(uint8_t motorNo)
//{
// return g_commuInfoBuff[motorNo];
//}

View File

@ -0,0 +1,84 @@
#ifndef _MOTORCOMMU_
#define _MOTORCOMMU_
#include "gd32f4xx.h"
#include "cfifo.h"
/*
********************************************************************************************************
* dma缓冲区相关
********************************************************************************************************
*/
typedef struct
{
int16_t dmaTranFlag; /*dma发送是否在工作的标志位*/
int32_t dmaSize; /*DMA缓冲区的大小*/
int32_t dmaOffset; /*获取数据在DMA缓冲区的偏移量*/
uint8_t *pDmaRsvBuff; /*指向接收DMA缓冲区的首地址*/
uint8_t *pDmaTraBuff; /*指向发送DMA缓冲区的首地址*/
CfifoBuff dataRsvCfifo; /*接受数据的循环缓冲区,串口---dma搬运--->pDmaRsvBuff[]--->dataRsvCfifo.BUFF[]*/
CfifoBuff dataTraCfifo; /*发送数据的循环缓冲区dataTraCfifo.BUFF[]--->pDmaTraBuff[]---dma搬运--->串口*/
}CommuInfo_t;
#define DMA_TRANS_IDLE 0//dma当前未在发送数据
#define DMA_TRANS_BUSY 1//dma当前正在发送数据
#define DMA_BUFF_SIZE 256//dma缓冲区大小
extern CommuInfo_t g_commuDeal;//来自motorCommu.c
/*
********************************************************************************************************
*
********************************************************************************************************
*/
#define H_MOTOR 0//数组g_motorCommuInitBuff[MOTOR_NUM]位号
#define V_MOTOR 1
/*-------------485接收发送宏开关----------------------*/
#define H_COMMU_RS485_TX gpio_bit_set(GPIOD, GPIO_PIN_10)//水平电机485发送
#define H_COMMU_RS485_RX gpio_bit_reset(GPIOD, GPIO_PIN_10)//水平电机485接收
#define V_COMMU_RS485_TX gpio_bit_set(GPIOC, GPIO_PIN_8)//垂直电机485发送
#define V_COMMU_RS485_RX gpio_bit_reset(GPIOC, GPIO_PIN_8)//垂直电机485接收
/**
* @brief
* @param
* @return
*/
void CommuDrvInit(void);
/**
* @brief
1
* @param motorNoH_MOTORV_MOTOR
* @param buffer
* @param len(DMA_BUFF_SIZE)
* @return
*/
int32_t CommuTransData(uint8_t motorNo, uint8_t* buffer, int32_t len);
/**
* @brief
* @param motorNoH_MOTORV_MOTOR
* @param userBuff
* @param len
* @return none
*/
void CommuRsvData(uint8_t motorNo, uint8_t* userBuff, uint32_t len);
/**
* @brief 485422,
* @param motorNoH_MOTORV_MOTOR
* @return rs485或rs422接收到的包数量
*/
uint16_t GetRsvFrameNum(uint8_t motorNo);
/**
* @brief 485422,
1
* @param motorNoH_MOTORV_MOTOR
* @return null
*/
void DecRsvFrameNum(uint8_t motorNo);
///*用于结构体数组赋值,方便外部使用此结构体数组*/
//CommuHwInfo_t GetMotorCommuBuffStr(uint8_t motorNo);
#endif

View File

@ -1,8 +1,80 @@
#include "servoMotor.h"
#include <ucos_ii.h>
/*
使
*/
static void MotorSwitchGpioCofig(void)
{
/*GPIO时钟初始化*/
rcu_periph_clock_enable(RCU_GPIOE);
/*水平电机打开引脚*/
gpio_mode_set(GPIOE, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, GPIO_PIN_0);
gpio_output_options_set(GPIOE, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, GPIO_PIN_0);
/*垂直电机打开引脚*/
gpio_mode_set(GPIOE, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, GPIO_PIN_1);
gpio_output_options_set(GPIOE, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, GPIO_PIN_1);
}
/*
crc校验高位 crc校验低位
01H 06H 02H 00H 00H 01H 49H B2H
*/
bool WriteMotorOneReg(uint8_t motorNo, uint16_t regAddr, uint16_t data)
{
uint8_t frameBuff[8] = {0};
uint8_t replyTemp[8];
uint16_t crc;
frameBuff[0] = 0x01;//由于采用一主一从模式所以水平电机垂直电机从机地址都是0x01云台后期也不会扩展
frameBuff[1] = WRITE_ONE_REG;
frameBuff[2] = regAddr >> 8;
frameBuff[3] = regAddr & 0xff;
frameBuff[4] = data >> 8;
frameBuff[5] = data & 0xff;
crc = ModbusCRC16(frameBuff, 6);
frameBuff[6] = crc & 0xff;
frameBuff[7] = crc >> 8;
CommuTransData(motorNo, frameBuff, 8);
OSTimeDlyHMSM(0u, 0u, 0u, 5u);//发送数据完成需要2ms接收电机返回的数据需要2ms延时5ms足够
CommuRsvData(motorNo, replyTemp, 8);//数据缓冲区已经有数据了才能调用此函数提取数据进行解析
for( uint8_t i = 0; i < 8; i++)
{
if ( frameBuff[i] != replyTemp[i] )
{
H_MOTOR_STOP;
return false;
}
}
return true;
}
/**
* @brief
* @param
* @return
*/
void servoMotorInit(void)
{
MotorSwitchGpioCofig();//两个电机电源的开关PE0,1引脚如果其它地方实现了可以不需要
H_MOTOR_OPEN;
OSTimeDlyHMSM(0u, 0u, 0u, 1000u);
V_MOTOR_OPEN;
CommuDrvInit();//伺服电机RS485通讯初始化
OSTimeDlyHMSM(0u, 0u, 0u, 500u);//等待硬件初始化成功
WriteMotorOneReg(H_MOTOR, H02_CONTR_MODE_SELEC, 0);//H0200,选择速度模式
WriteMotorOneReg(H_MOTOR, H04_DO1_FUNC_SELEC, 19);
WriteMotorOneReg(H_MOTOR, H06_SPEED_COMMU_SET_VALUE, 100);//速度设置为100rpm
WriteMotorOneReg(H_MOTOR, H06_SPEED_UP_SLOPE_VALUE, 3000);//加速度3000
WriteMotorOneReg(H_MOTOR, H06_SPEED_DOWN_SLOPE_VALUE, 2000);//减速度2000
WriteMotorOneReg(H_MOTOR, H03_DI1_LOGICAL_SELEC, 1);//只启动水平电机
}

View File

@ -1,8 +1,66 @@
#ifndef _DRIVER_SERVO_MOTOR_H_
#define _DRIVER_SERVO_MOTOR_H_
#ifndef _SERVOMOTOR_H_
#define _SERVOMOTOR_H_
#include "gd32f4xx.h"
#include "motorCommu.h"
#include "modbus_crc.h"
#include "stdbool.h"
/*
********************************************************************************************************
*
********************************************************************************************************
*/
#define H_MOTOR_OPEN gpio_bit_set(GPIOE,GPIO_PIN_0) //水平电机电源打开
#define H_MOTOR_STOP gpio_bit_reset(GPIOE,GPIO_PIN_0) //水平电机电源关闭
#define V_MOTOR_OPEN gpio_bit_set(GPIOE,GPIO_PIN_1) //垂直电机电源打开
#define V_MOTOR_STOP gpio_bit_reset(GPIOE,GPIO_PIN_1) //垂直电机电源关闭
/*
********************************************************************************************************
*
********************************************************************************************************
*/
#define READ_ONE_REG 0X03//读单个寄存器
#define READ_MULT_CONSE_REG 0X03//读多个连续的寄存器Read multiple consecutive registers
#define WRITE_ONE_REG 0X06//写单个寄存器
#define WRITE_MULT_CONSE_REG 0x10//写多个连续的寄存器
/*
********************************************************************************************************
*
********************************************************************************************************
*/
/*基本控制参数H02*/
#define H02_CONTR_MODE_SELEC 0X0200//Control mode selection控制模式选择0速度模式1位置模式2转矩模式
/*DI/DO参数H03~H04*/
#define H03_DI1_FUNC_SELEC 0X0302//DI1端子功能选择,一个 DI 功能选项只能关联一个 DI 端子,不可重复分配
#define H03_DI1_LOGICAL_SELEC 0X0303//DI1端子逻辑选择
#define H04_DO1_FUNC_SELEC 0X0400//DO1端子功能选择
#define H04_DO1_LOGICAL_SELEC 0X0401//DO1端子逻辑选择
/*速度控制参数H06*/
#define H06_SPEED_COMMAND_SELEC 0X0602//速度指令选择
#define H06_SPEED_COMMU_SET_VALUE 0X0603//速度指令通讯设置值,当 H06_02=0 时,通过此参数设定电机运行转速
#define H06_SPEED_UP_SLOPE_VALUE 0X0605//速度指令加速斜坡时间常数
#define H06_SPEED_DOWN_SLOPE_VALUE 0X0606//速度指令减速斜坡时间常数
#define H06_SPEED_REACH_MAX 0X0618//速度到达信号阈值
/*RS485通讯与功能参数H0C*/
#define H0C_COMMU_PARAM_EEPR_UPDATE 0X0C13//MODBUS通讯写入是否更新到 EEPROM设置1为写入
/*
crc校验高位 crc校验低位
01H 06H 02H 00H 00H 01H 49H B2H
*/
bool WriteMotorOneReg(uint8_t motorNo, uint16_t regAddr, uint16_t data);
/**
* @brief
* @param
* @return
*/
void servoMotorInit(void);
#endif

View File

@ -1,101 +1,47 @@
///Copyright (c) 2022, 四川汇源光通信有限公司
///All rights reserved.
///@file tmp75.C
///@brief tmp75驱动程序
///
///@details
///@note
///@author lqc
///@date 2022/05/23
///
///@version v1.0 2022/05/23 初始版本
/*************************************************
Copyright (c) 2025,
All rights reserved.
@file tmp75.C
@brief tmp75驱动程序
@details
@note
@author dufresne
@date 2025/09/15
@version v1.0 2025/09/15
*************************************************/
#include "tmp75.h"
/*
@ brief
@ param
@ return
@ note 2022-5-23
*/
static void delay_us(int us)
{
for(int i = 0; i < us; i++ )
{
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
asm("nop");
}
}
/*
@ brief tmp75芯片GPIO引脚
@ brief SDA引脚为输出模式
@ param
@ return
@ note 2022-5-23 lqc
*/
void temp75_gpio_init()
{
//配置引脚时钟
rcu_periph_clock_enable(RCU_GPIOB);
//设置引脚为输出模式:PB6
gpio_mode_set(GPIOB, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, GPIO_PIN_6);
gpio_output_options_set(GPIOB, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, GPIO_PIN_6);
//设置引脚PB7输出模式
gpio_mode_set(GPIOB, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, GPIO_PIN_7);
gpio_output_options_set(GPIOB, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, GPIO_PIN_7);
TMP75_SCL_HIGH;
TMP75_SDA_HIGH;
}
/*
@ brief SDA引脚为输出模式
@ param
@ return
@ note 2022-5-25 lqc
@ note 2025-09-15
*/
static void tmp75_sda_output()
{
gpio_mode_set(GPIOB, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, GPIO_PIN_7);
gpio_output_options_set(GPIOB, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, GPIO_PIN_7);
gpio_mode_set(GPIOB, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, I2C_SDA_PIN);
gpio_output_options_set(GPIOB, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, I2C_SDA_PIN);
}
/*
@ brief SDA引脚为输入模式
@ param
@ return
@ note 2022-5-25 lqc
@ param
@ return
@ note 2025-09-15
*/
static void tmp75_sda_input()
{
gpio_mode_set(GPIOB, GPIO_MODE_INPUT, GPIO_PUPD_NONE, GPIO_PIN_7);
// gpio_output_options_set(GPIOB, GPIO_PUPD_NONE, GPIO_OSPEED_50MHZ, GPIO_PIN_7);
gpio_mode_set(GPIOB, GPIO_MODE_INPUT, GPIO_PUPD_NONE, I2C_SDA_PIN);
}
/*
@ brief I2C start信号
@ param
@ return
@ note 2022-5-25
@ param
@ return
@ note 2025-09-15
*/
static void i2c_start()
{
@ -105,35 +51,37 @@ static void i2c_start()
delay_us(40);
}
/*
/*
@ brief I2C stop信号
@ param
@ return
@ note 2022-05-25
@ note 2025-09-15
*/
static void i2c_stop()
{
TMP75_SDA_LOW;
TMP75_SCL_HIGH;
TMP75_SDA_HIGH;
TMP75_SDA_HIGH;
}
/*
@ brief
@ param
@ return
@ note 2022-05-25
@ param
@ return
@ note 2025-09-15
*/
static void tmp75_write_byte(uint8_t byte)
{
for(int i = 0; i < 8; i++)
for (int i = 0; i < 8; i++)
{
TMP75_SCL_LOW;
delay_us(4);
if(byte & 0x80)
if (byte & 0x80)
{
TMP75_SDA_HIGH;
}else{
}
else
{
TMP75_SDA_LOW;
}
byte <<= 1;
@ -145,22 +93,22 @@ static void tmp75_write_byte(uint8_t byte)
/*
@ brief CPU接收TMP75返回的ACK信号
@ param
@ param
@ return
@ note
@ note 2025-09-15
*/
static void tmp75_ack()
{
int i = 0;
//将sda设置为输入模式
// 将sda设置为输入模式
tmp75_sda_input();
TMP75_SCL_HIGH;
while((TMP75_SDA_GET) && (i < 1000))
while ((TMP75_SDA_GET) && (i < 1000))
{
i++;
}
TMP75_SCL_LOW;
//将sda设置为输出模式
// 将sda设置为输出模式
tmp75_sda_output();
}
@ -168,7 +116,7 @@ static void tmp75_ack()
@ brief
@ param
@ return value:
@ note 2022-05-25
@ note 2025-09-15
*/
static uint8_t tmp75_read_byte()
{
@ -176,12 +124,12 @@ static uint8_t tmp75_read_byte()
tmp75_sda_input();
TMP75_SCL_LOW;
for(int i = 0; i < 8; i++)
for (int i = 0; i < 8; i++)
{
TMP75_SCL_HIGH;
value <<= 1;
delay_us(10);
if(TMP75_SDA_GET)
if (TMP75_SDA_GET)
{
value = value | 0x01;
}
@ -196,7 +144,7 @@ static uint8_t tmp75_read_byte()
@ brief ack信号
@ param
@ return
@ note 2022-05-25
@ note 2025-09-15
*/
static void master_ack()
{
@ -212,7 +160,7 @@ static void master_ack()
@ brief noack信号
@ param
@ return
@ note 2022-05-26
@ note 2025-09-15
*/
static void master_noack()
{
@ -223,52 +171,52 @@ static void master_noack()
TMP75_SCL_LOW;
delay_us(5);
}
/*
@ brief
@ param
@ param
@ return
@note 2022-05-25
@ note 2025-09-15
*/
float tmp75_read_temp(void)
{
uint8_t tempH = 0;
uint8_t tempL = 0;
uint16_t tempCode = 0;
float temp = 0;
//起始信号
static uint8_t tempH = 0;
static uint8_t tempL = 0;
static uint16_t tempCode = 0;
static float temp = 0;
// 起始信号
i2c_start();
//写tmp75地址
tmp75_write_byte(TMP75_ADDRESS);
//接收tmp75的ack信息
// 写tmp75地址
tmp75_write_byte(TMP75_ADDRESS << 1);//写 数据 设置
// 接收tmp75的ack信息
tmp75_ack();
//发送需读取数据的地址
tmp75_write_byte(TEMP_REGISTER_ADDRESS);
// 发送需读取数据的地址
tmp75_write_byte(TEMP_REGISTER_ADDRESS);// 写地址 0x00
tmp75_ack();
i2c_start();
//写tmp75地址
tmp75_write_byte(TMP75_ADDRESS + 1); //读地址数据
// 写tmp75地址
tmp75_write_byte((TMP75_ADDRESS << 1) + 1); // 读 数据 设置
tmp75_ack();
tempH = tmp75_read_byte();
master_ack();
tempL = tmp75_read_byte();
master_noack();
i2c_stop();
tempCode = (tempH << 8) | tempL;
tempCode = tempCode >> 6;
if(tempCode & 0x200) //负温度
if (tempCode & 0x200) // 负温度
{
tempCode &= 0x1ff;
temp = ((float)tempCode -512) / 4;
temp = ((float)tempCode - 512) / 4;
}
else
{
temp = (float)tempCode / 4;
}
TMP75_SDA_LOW;
TMP75_SCL_LOW;
TMP75_SCL_LOW;
return (temp);
}

View File

@ -13,19 +13,17 @@
#ifndef __TMP75_H_
#define __TMP75_H_
#include "gd32f4xx_gpio.h"
#include "gd32f4xx.h"
#include "drv_i2c.h"
#define TMP75_ADDRESS 0x90
#define TEMP_REGISTER_ADDRESS 0x00 //温度寄存器地址
#define TMP75_SCL_HIGH gpio_bit_set(GPIOB, GPIO_PIN_6)
#define TMP75_SCL_LOW gpio_bit_reset(GPIOB, GPIO_PIN_6)
#define TMP75_SCL_HIGH I2C_SCL_HIGH
#define TMP75_SCL_LOW I2C_SCL_LOW
#define TMP75_SDA_HIGH gpio_bit_set(GPIOB, GPIO_PIN_7)
#define TMP75_SDA_LOW gpio_bit_reset(GPIOB, GPIO_PIN_7)
#define TMP75_SDA_GET gpio_input_bit_get(GPIOB, GPIO_PIN_7)
#define TMP75_SDA_HIGH I2C_SDA_HIGH
#define TMP75_SDA_LOW I2C_SDA_LOW
#define TMP75_SDA_GET I2C_SDA_GET
void temp75_gpio_init();
float tmp75_read_temp(void);
#endif

View File

@ -2435,6 +2435,9 @@
<file>
<name>$PROJ_DIR$\..\APP\Device\Device_rotate\rotate_step.h</name>
</file>
<file>
<name>$PROJ_DIR$\..\APP\Device\Device_speed\servoMotor_recv.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\APP\Device\Device_speed\speed_to_bldc.c</name>
<configuration>
@ -2924,9 +2927,30 @@
</group>
<group>
<name>servoMotor</name>
<file>
<name>$PROJ_DIR$\..\BSP\Driver\servoMotor\cfifo.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\BSP\Driver\servoMotor\cfifo.h</name>
</file>
<file>
<name>$PROJ_DIR$\..\BSP\Driver\servoMotor\modbus_crc.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\BSP\Driver\servoMotor\modbus_crc.h</name>
</file>
<file>
<name>$PROJ_DIR$\..\BSP\Driver\servoMotor\motorCommu.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\BSP\Driver\servoMotor\motorCommu.h</name>
</file>
<file>
<name>$PROJ_DIR$\..\BSP\Driver\servoMotor\servoMotor.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\BSP\Driver\servoMotor\servoMotor.h</name>
</file>
</group>
<group>
<name>timer</name>
@ -2973,6 +2997,24 @@
<name>$PROJ_DIR$\..\BSP\Driver\w25q128\w25q128.h</name>
</file>
</group>
<file>
<name>$PROJ_DIR$\..\BSP\Driver\delay.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\BSP\Driver\delay.h</name>
</file>
<file>
<name>$PROJ_DIR$\..\BSP\Driver\drv_adc.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\BSP\Driver\drv_adc.h</name>
</file>
<file>
<name>$PROJ_DIR$\..\BSP\Driver\drv_i2c.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\BSP\Driver\drv_i2c.h</name>
</file>
</group>
<group>
<name>IAR</name>

View File

@ -3011,6 +3011,9 @@
<file>
<name>$PROJ_DIR$\..\APP\Device\Device_rotate\rotate_step.h</name>
</file>
<file>
<name>$PROJ_DIR$\..\APP\Device\Device_speed\servoMotor_recv.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\APP\Device\Device_speed\speed_to_bldc.c</name>
<configuration>
@ -3193,9 +3196,30 @@
</group>
<group>
<name>servoMotor</name>
<file>
<name>$PROJ_DIR$\..\BSP\Driver\servoMotor\cfifo.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\BSP\Driver\servoMotor\cfifo.h</name>
</file>
<file>
<name>$PROJ_DIR$\..\BSP\Driver\servoMotor\modbus_crc.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\BSP\Driver\servoMotor\modbus_crc.h</name>
</file>
<file>
<name>$PROJ_DIR$\..\BSP\Driver\servoMotor\motorCommu.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\BSP\Driver\servoMotor\motorCommu.h</name>
</file>
<file>
<name>$PROJ_DIR$\..\BSP\Driver\servoMotor\servoMotor.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\BSP\Driver\servoMotor\servoMotor.h</name>
</file>
</group>
<group>
<name>timer</name>
@ -3242,6 +3266,24 @@
<name>$PROJ_DIR$\..\BSP\Driver\w25q128\w25q128.h</name>
</file>
</group>
<file>
<name>$PROJ_DIR$\..\BSP\Driver\delay.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\BSP\Driver\delay.h</name>
</file>
<file>
<name>$PROJ_DIR$\..\BSP\Driver\drv_adc.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\BSP\Driver\drv_adc.h</name>
</file>
<file>
<name>$PROJ_DIR$\..\BSP\Driver\drv_i2c.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\BSP\Driver\drv_i2c.h</name>
</file>
</group>
<group>
<name>IAR</name>