From a2bbae0271d1b4ff8cbca8b8285eadf736893712 Mon Sep 17 00:00:00 2001
From: "REASEARCHER\\18383" <1633026436@qq.com>
Date: Thu, 16 Oct 2025 10:30:36 +0800
Subject: [PATCH] =?UTF-8?q?=E5=8F=91=E9=80=81=E6=8E=A5=E6=94=B6=E4=BF=AE?=
=?UTF-8?q?=E6=94=B9=E5=AE=8C=E6=AF=95=EF=BC=8C=E7=AD=89=E5=BE=85=E6=B5=8B?=
=?UTF-8?q?=E8=AF=95?=
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit
---
APP/Device/Device_speed/servoMotor_recv.c | 5 +-
APP/Device/Device_speed/speed_to_servoMotor.c | 10 +-
BSP/Driver/servoMotor/motorCommu.c | 193 ++++++------------
BSP/Driver/servoMotor/motorCommu.h | 8 +-
BSP/Driver/servoMotor/servoMotor.c | 135 +++++++-----
BSP/Driver/servoMotor/servoMotor.h | 25 ++-
PROJECT/OS2.ewp | 4 +-
7 files changed, 179 insertions(+), 201 deletions(-)
diff --git a/APP/Device/Device_speed/servoMotor_recv.c b/APP/Device/Device_speed/servoMotor_recv.c
index a266302..39f3248 100644
--- a/APP/Device/Device_speed/servoMotor_recv.c
+++ b/APP/Device/Device_speed/servoMotor_recv.c
@@ -21,7 +21,10 @@ static void ptz_recv_hori_servo_task()
while(1) {
OSSemPend(g_horiMotorMutex, 0, &err);
-
+ if ( MotorReplyForWrite(H_MOTOR) == true )
+ {
+ OSSemPost(g_horiSpeedMutex);
+ }
diff --git a/APP/Device/Device_speed/speed_to_servoMotor.c b/APP/Device/Device_speed/speed_to_servoMotor.c
index 49fe127..50bc663 100644
--- a/APP/Device/Device_speed/speed_to_servoMotor.c
+++ b/APP/Device/Device_speed/speed_to_servoMotor.c
@@ -289,8 +289,6 @@ static void creat_task_vert_servo_task(void)
}
}
-
-
void init_speed_module(void)
{
g_horiSpeedSem = OSSemCreate(0);
@@ -327,14 +325,12 @@ void init_speed_module(void)
creat_task_hori_servo_task();
creat_task_vert_servo_task();
+// creat_task_test();
OSTimeDlyHMSM(0u, 0u, 0u, 500u);//等待硬件初始化成功
-
- uint8_t buffer[20] = {0};
- uint8_t buffer_len = 0;
- buffer_len = WriteMotorOneReg_buffer(H_MOTOR, H02_CONTR_MODE_SELEC, 0, buffer);
- servoSendData(horiMotorType, buffer, buffer_len, lowPriority);
+ servoSendData(horiMotorType, WriteMotorOneReg(H_MOTOR, H02_CONTR_MODE_SELEC, 0)
+ , WRITE_ONE_REG_FRAME_NUM, lowPriority);
}
diff --git a/BSP/Driver/servoMotor/motorCommu.c b/BSP/Driver/servoMotor/motorCommu.c
index ccc61c4..b110b9b 100644
--- a/BSP/Driver/servoMotor/motorCommu.c
+++ b/BSP/Driver/servoMotor/motorCommu.c
@@ -99,11 +99,9 @@ static MotorCommuDmaHwInfo_t g_MotorDmaBuff[] =
********************************************************************************************************
*/
/* dmaջ */
-static uint8_t g_horiDmaRxBuff1[DMA_BUFF_SIZE] = {0};//ˮƽDMAܻ1
-static uint8_t g_horiDmaRxBuff2[DMA_BUFF_SIZE] = {0};//ˮƽDMAܻ2
+static uint8_t g_horiDmaRxBuff[DMA_BUFF_SIZE] = {0};//ˮƽDMAܻ
-static uint8_t g_vertDmaRxBuff1[DMA_BUFF_SIZE] = {0};//ֱDMAܻ1
-static uint8_t g_vertDmaRxBuff2[DMA_BUFF_SIZE] = {0};//ֱDMAܻ2
+static uint8_t g_vertDmaRxBuff[DMA_BUFF_SIZE] = {0};//ֱDMAܻ
/* ͨѶݻݽṹ */
static CommuInfo_t g_horiCommuDeal; //ˮƽ
static CommuInfo_t g_vertCommuDeal; //ֱ
@@ -111,22 +109,19 @@ static CommuInfo_t g_vertCommuDeal; //
typedef struct
{
CommuInfo_t* pCommuInfo; //ͨѶݻصݽṹ
- uint8_t* dmaRxBuff1; //dmaܻ1ָ
- uint8_t* dmaRxBuff2; //dmaܻ2ָ
+ uint8_t* dmaRxBuff; //dmaָܻ
}CommuHwInfo_t;//㻺ʼĽṹ
static CommuHwInfo_t g_commuInfoBuff[] =
{
//ˮƽ
{
.pCommuInfo = &g_horiCommuDeal,
- .dmaRxBuff1 = g_horiDmaRxBuff1,
- .dmaRxBuff2 = g_horiDmaRxBuff2,
+ .dmaRxBuff = g_horiDmaRxBuff,
},
//ֱ5
{
.pCommuInfo = &g_vertCommuDeal,
- .dmaRxBuff1 = g_vertDmaRxBuff1,
- .dmaRxBuff2 = g_vertDmaRxBuff2,
+ .dmaRxBuff = g_vertDmaRxBuff,
},
};
@@ -219,7 +214,7 @@ static void DmaCofig(void)
//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->pDmaRsvBuff1);
+ 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;
@@ -229,11 +224,11 @@ static void DmaCofig(void)
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_disable(g_MotorDmaBuff[i].dmaNo, g_MotorDmaBuff[i].dmaRxch);//ѭģʽ
+ 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);
+// 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);
}
}
@@ -257,9 +252,7 @@ static void CommuStructInit()
CommuInfo_t *pCommuDeal = g_commuInfoBuff[i].pCommuInfo;
pCommuDeal->dmaTranFlag = DMA_TRANS_IDLE;
pCommuDeal->dmaSize = DMA_BUFF_SIZE;
- pCommuDeal->pDmaRsvBuff1 = g_commuInfoBuff[i].dmaRxBuff1;
- pCommuDeal->pDmaRsvBuff2 = g_commuInfoBuff[i].dmaRxBuff2;
- pCommuDeal->pDmaRsvBuffSelect = DMA_RSVBUFF_SELECT1;//Ĭʹû1
+ pCommuDeal->pDmaRsvBuff = g_commuInfoBuff[i].dmaRxBuff;
}
}
@@ -321,38 +314,26 @@ void DMA0_Channel3_IRQHandler(void)
* @return
***********************************************************
*/
+static uint16_t g_horiLastPos;
+static uint16_t g_horiNowPos;
void USART2_IRQHandler(void)
{
/* ڵĽտжϷʽݻ档*/
- dma_single_data_parameter_struct dmaStruct;
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־λ
- //ͷź֪ͨյһݣԴ
+// CommuInfo_t *pCommuDeal = g_commuInfoBuff[H_MOTOR].pCommuInfo;
+
+ g_horiLastPos = g_horiNowPos;
+ g_horiNowPos = DMA_BUFF_SIZE - dma_transfer_number_get(g_MotorDmaBuff[H_MOTOR].dmaNo,
+ g_MotorDmaBuff[H_MOTOR].dmaRxch);
+
+ //ͷź֪ͨյһݣԴ
OSSemPost(g_horiMotorMutex);
- CommuInfo_t *pCommuDeal = g_commuInfoBuff[H_MOTOR].pCommuInfo;
- /* лʹýջϲĽԶӵһֽ*/
- if ( pCommuDeal->pDmaRsvBuffSelect == DMA_RSVBUFF_SELECT1 )
- {
- pCommuDeal->pDmaRsvBuffSelect = DMA_RSVBUFF_SELECT2;
- dma_channel_disable(g_MotorDmaBuff[H_MOTOR].dmaNo, g_MotorDmaBuff[H_MOTOR].dmaRxch);//лûҪȽDMA
- dmaStruct.memory0_addr = (uint32_t)(pCommuDeal->pDmaRsvBuff2);
- dma_single_data_mode_init(g_MotorDmaBuff[H_MOTOR].dmaNo, g_MotorDmaBuff[H_MOTOR].dmaRxch, &dmaStruct);
- dma_channel_enable(g_MotorDmaBuff[H_MOTOR].dmaNo, g_MotorDmaBuff[H_MOTOR].dmaRxch);
- }
- else
- {
- pCommuDeal->pDmaRsvBuffSelect = DMA_RSVBUFF_SELECT1;
- dma_channel_disable(g_MotorDmaBuff[H_MOTOR].dmaNo, g_MotorDmaBuff[H_MOTOR].dmaRxch);//лûҪȽDMA
- dmaStruct.memory0_addr = (uint32_t)(pCommuDeal->pDmaRsvBuff1);
- dma_single_data_mode_init(g_MotorDmaBuff[H_MOTOR].dmaNo, g_MotorDmaBuff[H_MOTOR].dmaRxch, &dmaStruct);
- dma_channel_enable(g_MotorDmaBuff[H_MOTOR].dmaNo, g_MotorDmaBuff[H_MOTOR].dmaRxch);
- }
-
-
+
/*DMAҪȡݳ*/
// DmaIdleNum = dma_transfer_number_get(g_MotorDmaBuff[H_MOTOR].dmaNo, g_MotorDmaBuff[H_MOTOR].dmaRxch);//ȡǻжٸû䣬Ѿ˶
}
@@ -361,41 +342,15 @@ void USART2_IRQHandler(void)
void DMA0_Channel1_IRQHandler(void)
{
- dma_single_data_parameter_struct dmaStruct;
/*
-* ϴ1ĽտжϡǸλDMAƫ
-* 1Ϊ˴1ĿжڴʱֹԽ磬 pUartAttr->DamOffsetΪ0;
-* 2DMAΪѭʽݰ˵ģõCntжϴ
-* 3ݹʱݽ´ʼλ;
-* 4ע⣺DMAΪģʽôһο,DMAԶdisable
+
+* ע⣺DMAΪģʽôһο,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;
- //ͷź֪ͨյһݣԴ
- OSSemPost(g_horiMotorMutex);
- /* лʹýջϲĽԶӵһֽ*/
- if ( pCommuDeal->pDmaRsvBuffSelect == DMA_RSVBUFF_SELECT1 )
- {
- pCommuDeal->pDmaRsvBuffSelect = DMA_RSVBUFF_SELECT2;
- dma_channel_disable(g_MotorDmaBuff[H_MOTOR].dmaNo, g_MotorDmaBuff[H_MOTOR].dmaRxch);//лûҪȽDMA
- dmaStruct.memory0_addr = (uint32_t)(pCommuDeal->pDmaRsvBuff2);
- dmaStruct.number = DMA_BUFF_SIZE;
- dma_single_data_mode_init(g_MotorDmaBuff[H_MOTOR].dmaNo, g_MotorDmaBuff[H_MOTOR].dmaRxch, &dmaStruct);
- dma_channel_enable(g_MotorDmaBuff[H_MOTOR].dmaNo, g_MotorDmaBuff[H_MOTOR].dmaRxch);
- }
- else
- {
- pCommuDeal->pDmaRsvBuffSelect = DMA_RSVBUFF_SELECT1;
- dma_channel_disable(g_MotorDmaBuff[H_MOTOR].dmaNo, g_MotorDmaBuff[H_MOTOR].dmaRxch);//лûҪȽDMA
- dmaStruct.memory0_addr = (uint32_t)(pCommuDeal->pDmaRsvBuff1);
- dmaStruct.number = DMA_BUFF_SIZE;
- dma_single_data_mode_init(g_MotorDmaBuff[H_MOTOR].dmaNo, g_MotorDmaBuff[H_MOTOR].dmaRxch, &dmaStruct);
- dma_channel_enable(g_MotorDmaBuff[H_MOTOR].dmaNo, g_MotorDmaBuff[H_MOTOR].dmaRxch);
- }
-
+
}
}
@@ -436,9 +391,10 @@ void DMA1_Channel7_IRQHandler(void)
* @return
***********************************************************
*/
+static uint16_t g_vertLastPos;
+static uint16_t g_vertNowPos;
void USART5_IRQHandler(void)
{
- dma_single_data_parameter_struct dmaStruct;
/* ڵĽտжϷʽݻ档*/
if(RESET != usart_interrupt_flag_get(g_motorCommuBuff[V_MOTOR].uartNo, USART_INT_FLAG_IDLE))
{
@@ -446,69 +402,26 @@ void USART5_IRQHandler(void)
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_vertLastPos = g_vertNowPos;
+ g_vertNowPos = DMA_BUFF_SIZE - dma_transfer_number_get(g_MotorDmaBuff[H_MOTOR].dmaNo,
+ g_MotorDmaBuff[H_MOTOR].dmaRxch);
//ͷź֪ͨյһݣԴ
- OSSemPost(g_horiMotorMutex);
- CommuInfo_t *pCommuDeal = g_commuInfoBuff[V_MOTOR].pCommuInfo;
- /* лʹýջϲĽԶӵһֽ*/
- if ( pCommuDeal->pDmaRsvBuffSelect == DMA_RSVBUFF_SELECT1 )
- {
- pCommuDeal->pDmaRsvBuffSelect = DMA_RSVBUFF_SELECT2;
- dma_channel_disable(g_MotorDmaBuff[V_MOTOR].dmaNo, g_MotorDmaBuff[V_MOTOR].dmaRxch);//лûҪȽDMA
- dmaStruct.memory0_addr = (uint32_t)(pCommuDeal->pDmaRsvBuff2);
- dma_single_data_mode_init(g_MotorDmaBuff[V_MOTOR].dmaNo, g_MotorDmaBuff[V_MOTOR].dmaRxch, &dmaStruct);
- dma_channel_enable(g_MotorDmaBuff[V_MOTOR].dmaNo, g_MotorDmaBuff[V_MOTOR].dmaRxch);
- }
- else
- {
- pCommuDeal->pDmaRsvBuffSelect = DMA_RSVBUFF_SELECT1;
- dma_channel_disable(g_MotorDmaBuff[V_MOTOR].dmaNo, g_MotorDmaBuff[V_MOTOR].dmaRxch);//лûҪȽDMA
- dmaStruct.memory0_addr = (uint32_t)(pCommuDeal->pDmaRsvBuff1);
- dma_single_data_mode_init(g_MotorDmaBuff[V_MOTOR].dmaNo, g_MotorDmaBuff[V_MOTOR].dmaRxch, &dmaStruct);
- dma_channel_enable(g_MotorDmaBuff[V_MOTOR].dmaNo, g_MotorDmaBuff[V_MOTOR].dmaRxch);
- }
+ OSSemPost(g_vertMotorMutex);
}
}
-
-// uint8_t rx_OK = 0;
void DMA1_Channel1_IRQHandler(void)
{
- dma_single_data_parameter_struct dmaStruct;
/*
-* ϴ1ĽտжϡǸλDMAƫ
-* 1Ϊ˴1ĿжڴʱֹԽ磬 pUartAttr->DamOffsetΪ0;
-* 2DMAΪѭʽݰ˵ģõCntжϴ
-* 3ݹʱݽ´ʼλ;
-* 4ע⣺DMAΪģʽôһο,DMAԶdisable
+* ע⣺DMAΪģʽôһο,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);
- CommuInfo_t *pCommuDeal = g_commuInfoBuff[V_MOTOR].pCommuInfo;
+// CommuInfo_t *pCommuDeal = g_commuInfoBuff[V_MOTOR].pCommuInfo;
//ͷź֪ͨյһݣԴ
- OSSemPost(g_horiMotorMutex);
- /* лʹýջϲĽԶӵһֽ*/
- if ( pCommuDeal->pDmaRsvBuffSelect == DMA_RSVBUFF_SELECT1 )
- {
- pCommuDeal->pDmaRsvBuffSelect = DMA_RSVBUFF_SELECT2;
- dma_channel_disable(g_MotorDmaBuff[V_MOTOR].dmaNo, g_MotorDmaBuff[V_MOTOR].dmaRxch);//лûҪȽDMA
- dmaStruct.memory0_addr = (uint32_t)(pCommuDeal->pDmaRsvBuff2);
- dmaStruct.number = DMA_BUFF_SIZE;
- dma_single_data_mode_init(g_MotorDmaBuff[V_MOTOR].dmaNo, g_MotorDmaBuff[V_MOTOR].dmaRxch, &dmaStruct);
- dma_channel_enable(g_MotorDmaBuff[V_MOTOR].dmaNo, g_MotorDmaBuff[V_MOTOR].dmaRxch);
- }
- else
- {
- pCommuDeal->pDmaRsvBuffSelect = DMA_RSVBUFF_SELECT1;
- dma_channel_disable(g_MotorDmaBuff[V_MOTOR].dmaNo, g_MotorDmaBuff[V_MOTOR].dmaRxch);//лûҪȽDMA
- dmaStruct.memory0_addr = (uint32_t)(pCommuDeal->pDmaRsvBuff1);
- dmaStruct.number = DMA_BUFF_SIZE;
- dma_single_data_mode_init(g_MotorDmaBuff[V_MOTOR].dmaNo, g_MotorDmaBuff[V_MOTOR].dmaRxch, &dmaStruct);
- dma_channel_enable(g_MotorDmaBuff[V_MOTOR].dmaNo, g_MotorDmaBuff[V_MOTOR].dmaRxch);
- }
-
-
+// OSSemPost(g_vertMotorMutex);
}
}
@@ -539,6 +452,13 @@ void CommuDrvInit(void)
*/
bool CommuTransData(uint8_t motorNo, uint8_t* buffer, int32_t len)
{
+
+ /*ж*/
+ if( buffer == NULL || len == 0 )
+ {
+ return false;
+ }
+ /*485лΪ*/
if( motorNo == H_MOTOR )
{
H_COMMU_RS485_TX;
@@ -563,20 +483,43 @@ bool CommuTransData(uint8_t motorNo, uint8_t* buffer, int32_t len)
/**
* @brief ӽѭжȡָȵݵû
* @param motorNoţH_MOTORˮƽV_MOTORֱ
-* @param userBuffӽѭнݵ
+* @param userBuffӽջнݵ
* @param lenݵij
* @return none
*/
-void CommuRsvData(uint8_t motorNo, uint8_t* userBuff, uint32_t len)
+bool CommuRsvData(uint8_t motorNo, uint8_t* userBuff, uint32_t len)
{
CommuInfo_t *pCommuDeal = g_commuInfoBuff[motorNo].pCommuInfo;
- if ( pCommuDeal->pDmaRsvBuffSelect == DMA_RSVBUFF_SELECT1 )
+ /*ж*/
+ if( userBuff == NULL || len == 0 )
{
- memcpy(userBuff, pCommuDeal->pDmaRsvBuff2, len);
+ return false;
+ }
+ /*DMA*/
+ if ( motorNo == H_MOTOR )
+ {
+ if ( ( (g_horiLastPos + len) % DMA_BUFF_SIZE ) != g_horiNowPos )//дĴϢ8ֽڣдط8ֽڴ
+ {
+ return false;
+ }
+ for(uint8_t i = 0; i < len; i++)
+ {
+ *(userBuff+i) = pCommuDeal->pDmaRsvBuff[g_horiLastPos];
+ g_horiLastPos = (g_horiLastPos + 1) % DMA_BUFF_SIZE;
+ }
}
else
{
- memcpy(userBuff, pCommuDeal->pDmaRsvBuff1, len);
- }
+ if ( ( (g_vertLastPos + len) % DMA_BUFF_SIZE ) != g_vertNowPos )//дĴϢ8ֽڣдط8ֽڴ
+ {
+ return false;
+ }
+ for(uint8_t i = 0; i < len; i++)
+ {
+ *(userBuff+i) = pCommuDeal->pDmaRsvBuff[g_vertLastPos];
+ g_horiLastPos = (g_vertLastPos + 1) % DMA_BUFF_SIZE;
+ }
+ }
+ return true;
}
diff --git a/BSP/Driver/servoMotor/motorCommu.h b/BSP/Driver/servoMotor/motorCommu.h
index 5298097..70b1b99 100644
--- a/BSP/Driver/servoMotor/motorCommu.h
+++ b/BSP/Driver/servoMotor/motorCommu.h
@@ -13,16 +13,12 @@ typedef struct
{
int16_t dmaTranFlag; /*dmaǷڹı־λ*/
int32_t dmaSize; /*DMAջĴС*/
- uint8_t *pDmaRsvBuff1; /*ָDMA1ַ*/
- uint8_t *pDmaRsvBuff2; /*ָDMA2ַ*/
- uint8_t pDmaRsvBuffSelect; /*ʾǰʹĸջ*/
+ uint8_t *pDmaRsvBuff; /*ָDMAַ*/
}CommuInfo_t;
#define DMA_TRANS_IDLE 0//dmaǰδڷ
#define DMA_TRANS_BUSY 1//dmaǰڷ
#define DMA_BUFF_SIZE 64//dmaС
-#define DMA_RSVBUFF_SELECT1 (uint8_t)(0)//ǰʹdmaջ1
-#define DMA_RSVBUFF_SELECT2 (uint8_t)(1)//ǰʹdmaջ2
//extern CommuInfo_t g_commuDeal;//motorCommu.c
@@ -63,7 +59,7 @@ bool CommuTransData(uint8_t motorNo, uint8_t* buffer, int32_t len);
* @param lenݵij
* @return none
*/
-void CommuRsvData(uint8_t motorNo, uint8_t* userBuff, uint32_t len);
+bool CommuRsvData(uint8_t motorNo, uint8_t* userBuff, uint32_t len);
///*ڽṹ鸳ֵⲿʹô˽ṹ*/
diff --git a/BSP/Driver/servoMotor/servoMotor.c b/BSP/Driver/servoMotor/servoMotor.c
index 20cf02c..5d25d21 100644
--- a/BSP/Driver/servoMotor/servoMotor.c
+++ b/BSP/Driver/servoMotor/servoMotor.c
@@ -16,8 +16,6 @@ static void MotorSwitchGpioCofig(void)
}
-static uint8_t g_writeOneRegBuff[WRITE_ONE_REG_BUFFNUM];//дĴصݺдȫһ£
-
/*
ӻַ Ĵַ Ĵַ ݸλ ݵλ crcУλ crcУλ
@@ -28,93 +26,122 @@ static uint8_t g_writeOneRegBuff[WRITE_ONE_REG_BUFFNUM];//
* @param motorNoдֱˮƽ
* @param regAddrҪдļĴ
* @param dataҪĴд
-* @return false:дʧܣǰDMAڷ
+* @return ַ
*/
-bool WriteMotorOneReg(uint8_t motorNo, uint16_t regAddr, uint16_t data)
+static uint8_t g_writeOneRegBuff[WRITE_ONE_REG_FRAME_NUM];
+uint8_t* WriteMotorOneReg(uint8_t motorNo, uint16_t regAddr, uint16_t data)
{
- uint8_t frameBuff[WRITE_ONE_REG_BUFFNUM] = {0};
uint16_t crc;
if ( motorNo == H_MOTOR )
{
- frameBuff[0] = H_MOTOR_ADDR;//ڲһһģʽˮƽֱӻַ0x01̨Ҳչ
+ g_writeOneRegBuff[0] = H_MOTOR_ADDR;//ڲһһģʽˮƽֱӻַ0x01̨Ҳչ
}
else
{
- frameBuff[0] = V_MOTOR_ADDR;
+ g_writeOneRegBuff[0] = V_MOTOR_ADDR;
}
- frameBuff[1] = WRITE_ONE_REG;
- frameBuff[2] = regAddr >> WRITE_ONE_REG_BUFFNUM;
- frameBuff[3] = regAddr & 0xff;
- frameBuff[4] = data >> WRITE_ONE_REG_BUFFNUM;
- frameBuff[5] = data & 0xff;
- crc = ModbusCRC16(frameBuff, WRITE_ONE_REG_BUFFNUM - 2);
- frameBuff[6] = crc & 0xff;
- frameBuff[7] = crc >> WRITE_ONE_REG_BUFFNUM;
-
- if ( CommuTransData(motorNo, frameBuff, WRITE_ONE_REG_BUFFNUM) == false)
- {
- return false;
- }
- memcpy(g_writeOneRegBuff, frameBuff, WRITE_ONE_REG_BUFFNUM);
- return true;
+ g_writeOneRegBuff[1] = WRITE_ONE_REG;
+ g_writeOneRegBuff[2] = regAddr >> 8;
+ g_writeOneRegBuff[3] = regAddr & 0xff;
+ g_writeOneRegBuff[4] = data >> 8;
+ g_writeOneRegBuff[5] = data & 0xff;
+ crc = ModbusCRC16(g_writeOneRegBuff, WRITE_ONE_REG_FRAME_NUM - 2);
+ g_writeOneRegBuff[6] = crc & 0xff;
+ g_writeOneRegBuff[7] = crc >> 8;
+ return g_writeOneRegBuff;
}
+
/**
* @brief дĴɹ᷵һ֡дʽȫһµ
* @param motorNoдֱˮƽ
-* @param userBuffշصݵ
-* @param lenյݳȣڴ˺ΪWRITE_ONE_REG_BUFFNUM
* @return false:дݲһ
*/
-bool MotorReplyForWrite(uint8_t motorNo, uint8_t* userBuff, uint8_t len)
+bool MotorReplyForWrite(uint8_t motorNo)
{
- CommuRsvData(motorNo, userBuff, len);
- for( uint8_t i = 0; i < len; i++ )
+ static uint8_t motorReplybuff[WRITE_ONE_REG_FRAME_NUM];
+ /*ȡʧ*/
+ if ( CommuRsvData(motorNo, motorReplybuff, WRITE_ONE_REG_FRAME_NUM) == false )
{
- if ( userBuff[i] != g_writeOneRegBuff[i] )
+ return false;
+ }
+ else
+ {
+ for( uint8_t i = 0; i < WRITE_ONE_REG_FRAME_NUM; i++ )
{
- memset(g_writeOneRegBuff, 0x00, len);
- return false;
+ /*ȡݲ*/
+ if ( motorReplybuff[i] != g_writeOneRegBuff[i] )
+ {
+ return false;
+ }
}
}
- memset(g_writeOneRegBuff, 0x00, len);
return true;
}
/*
-ӻַ Ĵַ Ĵַ ݸλ ݵλ crcУλ crcУλ
- 01H 06H 02H 00H 00H 01H 49H B2H
+ӻַ Ĵַ Ĵַ regλ λ crcУλ crcУλ
+ 01H 03H 0BH 00H 00H 01H 86H 2EH
*/
/**
-* @brief ŷٶģʽдĴ
-* @param motorNoдֱˮƽ
-* @param regAddrҪдļĴ
-* @param dataҪĴд
-* @param frameBuff: ͵
-* @return дframeBuffij
+* @brief ŷٶģʽĴ
+* @param motorNoֱˮƽ
+* @param regAddrҪļĴ
+* @return ַ
*/
-uint8_t WriteMotorOneReg_buffer(uint8_t motorNo, uint16_t regAddr, uint16_t data, uint8_t *frameBuff)
+static uint8_t g_readOneRegBuff[READ_ONE_REG_FRAME_NUM];
+uint8_t* ReadMotorOneReg(uint8_t motorNo, uint16_t regAddr)
{
- uint16_t crc;
- if ( motorNo == H_MOTOR )
+ uint16_t crc;
+ if ( motorNo == H_MOTOR )
+ {
+ g_readOneRegBuff[0] = H_MOTOR_ADDR;//ڲһһģʽˮƽֱӻַ0x01̨Ҳչ
+ }
+ else
+ {
+ g_readOneRegBuff[0] = V_MOTOR_ADDR;
+ }
+ g_readOneRegBuff[1] = READ_ONE_REG;
+ g_readOneRegBuff[2] = regAddr >> 8;
+ g_readOneRegBuff[3] = regAddr & 0xff;
+ g_readOneRegBuff[4] = 0x00;
+ g_readOneRegBuff[5] = 0x01;
+ crc = ModbusCRC16(g_readOneRegBuff, READ_ONE_REG_FRAME_NUM - 2);
+ g_readOneRegBuff[6] = crc & 0xff;
+ g_readOneRegBuff[7] = crc >> 8;
+ return g_readOneRegBuff;
+}
+/*
+ӻַ ֽ ݸλ ݵλ crcУλ crcУλ
+ 01H 03H 02H 00H 00H B8H 44H
+*/
+/**
+* @brief Ĵͳɹ᷵һ֡7ֽڵ
+* @param motorNoдֱˮƽ
+* @param dataдֱˮƽ
+* @return false:дݲһ
+*/
+bool MotorReplyForRead(uint8_t motorNo, uint16_t* data)
+{
+ /*ж*/
+ if ( data == NULL )
{
- frameBuff[0] = H_MOTOR_ADDR;//ڲһһģʽˮƽֱӻַ0x01̨Ҳչ
+ return false;
+ }
+ static uint8_t motorReplybuff[WRITE_ONE_REG_FRAME_NUM - 1];
+ /*ȡʧ*/
+ if ( CommuRsvData(motorNo, motorReplybuff, WRITE_ONE_REG_FRAME_NUM - 1) == false )
+ {
+ return false;
}
else
{
- frameBuff[0] = V_MOTOR_ADDR;
+ *data = motorReplybuff[3];
+ *data = (*data << 8) | motorReplybuff[4];
}
- frameBuff[1] = WRITE_ONE_REG;
- frameBuff[2] = regAddr >> WRITE_ONE_REG_BUFFNUM;
- frameBuff[3] = regAddr & 0xff;
- frameBuff[4] = data >> WRITE_ONE_REG_BUFFNUM;
- frameBuff[5] = data & 0xff;
- crc = ModbusCRC16(frameBuff, WRITE_ONE_REG_BUFFNUM - 2);
- frameBuff[6] = crc & 0xff;
- frameBuff[7] = crc >> WRITE_ONE_REG_BUFFNUM;
-
- return 8;
+ return true;
}
+
/**
* @brief ŷʼ
* @param
diff --git a/BSP/Driver/servoMotor/servoMotor.h b/BSP/Driver/servoMotor/servoMotor.h
index a4d70e7..006e48f 100644
--- a/BSP/Driver/servoMotor/servoMotor.h
+++ b/BSP/Driver/servoMotor/servoMotor.h
@@ -26,7 +26,8 @@
#define WRITE_ONE_REG 0X06//дĴ
#define WRITE_MULT_CONSE_REG 0x10//дļĴ
-#define WRITE_ONE_REG_BUFFNUM 8//дĴֽ֡ڸ
+#define WRITE_ONE_REG_FRAME_NUM 8//дĴֽ֡ڸ
+#define READ_ONE_REG_FRAME_NUM 8//Ĵֽ֡ڸ
/*
********************************************************************************************************
* Ĵ
@@ -61,23 +62,35 @@
* @param dataҪĴд
* @return false:дʧܣǰDMAڷ
*/
-bool WriteMotorOneReg(uint8_t motorNo, uint16_t regAddr, uint16_t data);
+uint8_t* WriteMotorOneReg(uint8_t motorNo, uint16_t regAddr, uint16_t data);
/**
* @brief дĴɹ᷵һ֡дʽȫһµ
* @param motorNoдֱˮƽ
-* @param userBuffշصݵ
-* @param lenյݳȣڴ˺ΪWRITE_ONE_REG_BUFFNUM
* @return false:дݲһ
*/
-bool MotorReplyForWrite(uint8_t motorNo, uint8_t* userBuff, uint8_t len);
+bool MotorReplyForWrite(uint8_t motorNo);
+/**
+* @brief ŷٶģʽĴ
+* @param motorNoֱˮƽ
+* @param regAddrҪļĴ
+* @return ַ
+*/
+uint8_t* ReadMotorOneReg(uint8_t motorNo, uint16_t regAddr);
+
+/**
+* @brief Ĵͳɹ᷵һ֡7ֽڵ
+* @param motorNoдֱˮƽ
+* @param dataдֱˮƽ
+* @return false:дݲһ
+*/
+bool MotorReplyForRead(uint8_t motorNo, uint16_t* data);
/**
* @brief ŷʼ
* @param
* @return
*/
void servoMotorInit(void);
-uint8_t WriteMotorOneReg_buffer(uint8_t motorNo, uint16_t regAddr, uint16_t data, uint8_t *frameBuff);
#endif
\ No newline at end of file
diff --git a/PROJECT/OS2.ewp b/PROJECT/OS2.ewp
index a2f27a5..571960f 100644
--- a/PROJECT/OS2.ewp
+++ b/PROJECT/OS2.ewp
@@ -741,7 +741,7 @@
- 56
+ 1
inputOutputBased
@@ -826,7 +826,7 @@