diff --git a/.vscode/iar-vsc.json b/.vscode/iar-vsc.json
new file mode 100644
index 0000000..a1da56b
--- /dev/null
+++ b/.vscode/iar-vsc.json
@@ -0,0 +1,18 @@
+{
+ "workspace": {
+ "path": "${workspaceFolder}\\PROJECT\\OS2.eww"
+ },
+ "workspaces": {
+ "${workspaceFolder}\\PROJECT\\OS2.eww": {
+ "configs": {
+ "${workspaceFolder}\\PROJECT\\OS2.ewp": "Debug"
+ },
+ "selected": {
+ "path": "${workspaceFolder}\\PROJECT\\OS2.ewp"
+ }
+ }
+ },
+ "workbench": {
+ "path": "D:\\IAR"
+ }
+}
\ No newline at end of file
diff --git a/.vscode/settings.json b/.vscode/settings.json
index 1adce06..e47d268 100644
--- a/.vscode/settings.json
+++ b/.vscode/settings.json
@@ -46,6 +46,16 @@
"comm_cfginfo.h": "c",
"servomotor.h": "c",
"pdebug.h": "c",
- "limits": "c"
+ "limits": "c",
+ "motorcommu.h": "c",
+ "stdbool.h": "c",
+ "cfifo.h": "c",
+ "servomotor_recv.h": "c",
+ "ucos_ii.h": "c",
+ "__config": "c",
+ "utility": "c",
+ "exception": "c",
+ "new": "c",
+ "cstdio": "c"
}
}
\ No newline at end of file
diff --git a/APP/Device/Device_speed/servoMotor_recv.c b/APP/Device/Device_speed/servoMotor_recv.c
index db6dc5a..e932d05 100644
--- a/APP/Device/Device_speed/servoMotor_recv.c
+++ b/APP/Device/Device_speed/servoMotor_recv.c
@@ -2,6 +2,7 @@
#include "ptz_header_file.h"
#include "servoMotor.h"
+
#ifdef PTZ_SERVO_MOTOR
//电机数据解析任务互斥量
diff --git a/APP/Device/Device_speed/servoMotor_recv.h b/APP/Device/Device_speed/servoMotor_recv.h
index 2fdaae3..41a5e31 100644
--- a/APP/Device/Device_speed/servoMotor_recv.h
+++ b/APP/Device/Device_speed/servoMotor_recv.h
@@ -1,15 +1,16 @@
-#ifndef __DEVICE_SPEED_SERVOMOTOR_H_
-#define __DEVICE_SPEED_SERVOMOTOR_H_
+#ifndef __SERVOMOTOR_RECV_H_
+#define __SERVOMOTOR_RECV_H_
#include "ptz_type_select.h"
+#include "bsp_os.h"
+
+ #ifdef PTZ_SERVO_MOTOR
+
+ extern BSP_OS_SEM g_horiMotorMutex;
+ extern BSP_OS_SEM g_vertMotorMutex;
+
+ void Init_ServoMotorRecv(void);
-#ifdef PTZ_SERVO_MOTOR
-
-
-
-void Init_ServoMotorRecv(void);
-
-
+ #endif
-#endif
#endif
diff --git a/APP/Device/Device_speed/speed_to_servoMotor.c b/APP/Device/Device_speed/speed_to_servoMotor.c
index 0acf1e4..5453241 100644
--- a/APP/Device/Device_speed/speed_to_servoMotor.c
+++ b/APP/Device/Device_speed/speed_to_servoMotor.c
@@ -178,7 +178,7 @@ static void ptz_hori_servo_task()
//发送数据
-
+
g_servoMotorLinkList.horiMotor.linkListNum = highPriority;
continue;
}
diff --git a/BSP/Driver/servoMotor/motorCommu.c b/BSP/Driver/servoMotor/motorCommu.c
index 2cd5864..3677bcb 100644
--- a/BSP/Driver/servoMotor/motorCommu.c
+++ b/BSP/Driver/servoMotor/motorCommu.c
@@ -1,6 +1,5 @@
#include "motorCommu.h"
-
-
+#include "servoMotor_recv.h"
/*
********************************************************************************************************
@@ -99,11 +98,12 @@ static MotorCommuDmaHwInfo_t g_MotorDmaBuff[] =
* ͨѶʼṹ
********************************************************************************************************
*/
-/* 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ܻ
+/* 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_vertDmaRxBuff1[DMA_BUFF_SIZE] = {0};//ֱDMAܻ1
+static uint8_t g_vertDmaRxBuff2[DMA_BUFF_SIZE] = {0};//ֱDMAܻ2
/* ͨѶݻݽṹ */
static CommuInfo_t g_horiCommuDeal; //ˮƽ
static CommuInfo_t g_vertCommuDeal; //ֱ
@@ -111,22 +111,22 @@ static CommuInfo_t g_vertCommuDeal; //
typedef struct
{
CommuInfo_t* pCommuInfo; //ͨѶݻصݽṹ
- uint8_t* dmaTxBuff; //dmaͻָ
- uint8_t* dmaRxBuff; //dmaָܻ
+ uint8_t* dmaRxBuff1; //dmaܻ1ָ
+ uint8_t* dmaRxBuff2; //dmaܻ2ָ
}CommuHwInfo_t;//㻺ʼĽṹ
static CommuHwInfo_t g_commuInfoBuff[] =
{
//ˮƽ
{
.pCommuInfo = &g_horiCommuDeal,
- .dmaTxBuff = g_horiDmaTxBuff,
- .dmaRxBuff = g_horiDmaRxBuff,
+ .dmaRxBuff1 = g_horiDmaRxBuff1,
+ .dmaRxBuff2 = g_horiDmaRxBuff2,
},
//ֱ5
{
.pCommuInfo = &g_vertCommuDeal,
- .dmaTxBuff = g_vertDmaTxBuff,
- .dmaRxBuff = g_vertDmaRxBuff,
+ .dmaRxBuff1 = g_vertDmaRxBuff1,
+ .dmaRxBuff2 = g_vertDmaRxBuff2,
},
};
@@ -219,7 +219,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->pDmaRsvBuff);
+ dmaStruct.memory0_addr = (uint32_t)(g_commuInfoBuff[i].pCommuInfo->pDmaRsvBuff1);
dmaStruct.memory_inc = DMA_MEMORY_INCREASE_ENABLE;
dmaStruct.number = DMA_BUFF_SIZE;
dmaStruct.periph_addr = g_MotorDmaBuff[i].periphAddr;
@@ -229,7 +229,7 @@ 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_enable(g_MotorDmaBuff[i].dmaNo, g_MotorDmaBuff[i].dmaRxch);//ѭģʽ
+ dma_circulation_disable(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);
@@ -244,7 +244,7 @@ static void DmaCofig(void)
********************************************************************************************************
*/
/*!
- \brief ʼڵĻָ롢DMAĿռСDMAƫͽնеijʼ
+ \brief ʼڵĻ
\param[in] none
\param[out] none
\retval none
@@ -255,13 +255,11 @@ static void CommuStructInit()
{
/*ΪԵIJֵ*/
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); //ݷ
+ pCommuDeal->pDmaRsvBuff1 = g_commuInfoBuff[i].dmaRxBuff1;
+ pCommuDeal->pDmaRsvBuff2 = g_commuInfoBuff[i].dmaRxBuff2;
+ pCommuDeal->pDmaRsvBuffSelect = DMA_RSVBUFF_SELECT1;//Ĭʹû1
}
}
@@ -305,25 +303,14 @@ 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;
- }
+ while(usart_flag_get(g_motorCommuBuff[H_MOTOR].uartNo, USART_FLAG_TC) == RESET); // ȴڷ
+ H_COMMU_RS485_RX; //485лΪ
+ pCommuDeal->dmaTranFlag = DMA_TRANS_IDLE;
}
}
@@ -334,43 +321,47 @@ void DMA0_Channel3_IRQHandler(void)
* @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
+ 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־λ
- g_hFrameRcvNum++;
-
+ //ͷź֪ͨյһݣԴ
+ 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);//ȡǻжٸû䣬Ѿ˶
- 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;
+ // DmaIdleNum = dma_transfer_number_get(g_MotorDmaBuff[H_MOTOR].dmaNo, g_MotorDmaBuff[H_MOTOR].dmaRxch);//ȡǻжٸû䣬Ѿ˶
}
}
void DMA0_Channel1_IRQHandler(void)
{
- int32_t RecvNum = 0;
- int32_t WriteNum = 0;
+ dma_single_data_parameter_struct dmaStruct;
/*
* ϴ1ĽտжϡǸλDMAƫ
* 1Ϊ˴1ĿжڴʱֹԽ磬 pUartAttr->DamOffsetΪ0;
@@ -383,17 +374,28 @@ void DMA0_Channel1_IRQHandler(void)
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)
+ //ͷź֪ͨյһݣԴ
+ OSSemPost(g_horiMotorMutex);
+ /* лʹýջϲĽԶӵһֽ*/
+ if ( pCommuDeal->pDmaRsvBuffSelect == DMA_RSVBUFF_SELECT1 )
{
- /*add deal here*/
+ 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);
}
- /*λDMAƫ*/
- pCommuDeal->dmaOffset = 0;
+ 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);
+ }
+
}
}
@@ -414,27 +416,16 @@ 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лΪ
+ while(usart_flag_get(g_motorCommuBuff[V_MOTOR].uartNo, USART_FLAG_TC) == RESET); // ȴڷ
+ V_COMMU_RS485_RX; //485лΪ
+ pCommuDeal->dmaTranFlag = DMA_TRANS_IDLE;
+
}
}
@@ -445,35 +436,36 @@ void DMA1_Channel7_IRQHandler(void)
* @return
***********************************************************
*/
-static uint16_t g_vFrameRcvNum = 0;
void USART5_IRQHandler(void)
-{
+{
+ dma_single_data_parameter_struct dmaStruct;
/* ڵĽտжϷʽݻ档*/
- 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++;
-
+ //ͷź֪ͨյһݣԴ
+ OSSemPost(g_horiMotorMutex);
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)
+ /* лʹýջϲĽԶӵһֽ*/
+ if ( pCommuDeal->pDmaRsvBuffSelect == DMA_RSVBUFF_SELECT1 )
{
- printf("Uart ReadFifo is not enough\r\n");
+ 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);
}
- /*ȡλõƫ*/
- pCommuDeal->dmaOffset += RecvNum;
}
}
@@ -481,8 +473,7 @@ void USART5_IRQHandler(void)
// uint8_t rx_OK = 0;
void DMA1_Channel1_IRQHandler(void)
{
- int32_t RecvNum = 0;
- int32_t WriteNum = 0;
+ dma_single_data_parameter_struct dmaStruct;
/*
* ϴ1ĽտжϡǸλDMAƫ
* 1Ϊ˴1ĿжڴʱֹԽ磬 pUartAttr->DamOffsetΪ0;
@@ -493,20 +484,31 @@ void DMA1_Channel1_IRQHandler(void)
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)
+ //ͷź֪ͨյһݣԴ
+ OSSemPost(g_horiMotorMutex);
+ /* лʹýջϲĽԶӵһֽ*/
+ if ( pCommuDeal->pDmaRsvBuffSelect == DMA_RSVBUFF_SELECT1 )
{
- /*add deal here*/
+ 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);
}
- /*λDMAƫ*/
- pCommuDeal->dmaOffset = 0;
+ 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);
+ }
+
+
}
}
@@ -529,20 +531,14 @@ void CommuDrvInit(void)
}
/**
-* @brief ͨѭеķʽݵķ
- ݣʾѾյİı1
+* @brief ݵķ
* @param motorNoţH_MOTORˮƽV_MOTORֱ
-* @param bufferͻ
-* @param lenݵij(ôDMA_BUFF_SIZE)
-* @return д뷢ͻij
+* @param bufferҪ͵
+* @param lenݵij
+* @return ture:DMAеǰݿԷͣfalseDMAڷݣǰݲܷ
*/
-int32_t CommuTransData(uint8_t motorNo, uint8_t* buffer, int32_t len)
+bool 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;
@@ -553,22 +549,15 @@ int32_t CommuTransData(uint8_t motorNo, uint8_t* buffer, int32_t len)
}
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);
- }
+
+ pCommuDeal->dmaTranFlag = DMA_TRANS_BUSY;
+ CommuDmaTra(motorNo, buffer, len);
+ return true;
}
- return TransNum;
+ return false;
}
/**
@@ -580,55 +569,14 @@ int32_t CommuTransData(uint8_t motorNo, uint8_t* buffer, int32_t len)
*/
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 motorNoţH_MOTORˮƽV_MOTORֱ
-* @return rs485rs422յİ
-*/
-uint16_t GetRsvFrameNum(uint8_t motorNo)
-{
- if (motorNo == H_MOTOR)
+ if ( pCommuDeal->pDmaRsvBuffSelect == DMA_RSVBUFF_SELECT1 )
{
- return g_hFrameRcvNum;
+ memcpy(userBuff, pCommuDeal->pDmaRsvBuff2, len);
}
-
- return g_vFrameRcvNum;
-}
-/**
-* @brief ⲿͨѶ485422ӿ,ÿӻһ
- ݣʾѾյİı1
-* @param motorNoţH_MOTORˮƽV_MOTORֱ
-* @return null
-*/
-void DecRsvFrameNum(uint8_t motorNo)
-{
- if (motorNo == H_MOTOR && g_hFrameRcvNum > 0)
+ else
{
- g_hFrameRcvNum--;
- return;
- }
- if (motorNo == V_MOTOR && g_vFrameRcvNum > 0)
- {
- g_vFrameRcvNum--;
- return;
+ memcpy(userBuff, pCommuDeal->pDmaRsvBuff1, len);
}
}
-
-///*ڽṹ鸳ֵⲿʹô˽ṹ*/
-//CommuHwInfo_t GetMotorCommuBuffStr(uint8_t motorNo)
-//{
-// return g_commuInfoBuff[motorNo];
-//}
\ No newline at end of file
diff --git a/BSP/Driver/servoMotor/motorCommu.h b/BSP/Driver/servoMotor/motorCommu.h
index 4fd2c1a..5298097 100644
--- a/BSP/Driver/servoMotor/motorCommu.h
+++ b/BSP/Driver/servoMotor/motorCommu.h
@@ -1,8 +1,9 @@
-#ifndef _MOTORCOMMU_
-#define _MOTORCOMMU_
+#ifndef _MOTORCOMMU_H_
+#define _MOTORCOMMU_H_
#include "gd32f4xx.h"
-#include "cfifo.h"
+#include "stdbool.h"
+#include "string.h"
/*
********************************************************************************************************
* dma
@@ -11,18 +12,19 @@
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ˣ--->*/
+ int32_t dmaSize; /*DMAջĴС*/
+ uint8_t *pDmaRsvBuff1; /*ָDMA1ַ*/
+ uint8_t *pDmaRsvBuff2; /*ָDMA2ַ*/
+ uint8_t pDmaRsvBuffSelect; /*ʾǰʹĸջ*/
}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 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
/*
********************************************************************************************************
@@ -46,14 +48,13 @@ extern CommuInfo_t g_commuDeal;//
void CommuDrvInit(void);
/**
-* @brief ͨѭеķʽݵķ
- ݣʾѾյİı1
+* @brief ݵķ
* @param motorNoţH_MOTORˮƽV_MOTORֱ
-* @param bufferͻ
-* @param lenݵij(ôDMA_BUFF_SIZE)
-* @return д뷢ͻij
+* @param bufferҪ͵
+* @param lenݵij
+* @return ture:DMAеǰݿԷͣfalseDMAڷݣǰݲܷ
*/
-int32_t CommuTransData(uint8_t motorNo, uint8_t* buffer, int32_t len);
+bool CommuTransData(uint8_t motorNo, uint8_t* buffer, int32_t len);
/**
* @brief ӽѭжȡָȵݵû
@@ -64,20 +65,6 @@ int32_t CommuTransData(uint8_t motorNo, uint8_t* buffer, int32_t len);
*/
void CommuRsvData(uint8_t motorNo, uint8_t* userBuff, uint32_t len);
-/**
-* @brief ⲿͨѶ485422ӿ,յİ
-* @param motorNoţH_MOTORˮƽV_MOTORֱ
-* @return rs485rs422յİ
-*/
-uint16_t GetRsvFrameNum(uint8_t motorNo);
-
-/**
-* @brief ⲿͨѶ485422ӿ,ÿӻһ
- ݣʾѾյİı1
-* @param motorNoţH_MOTORˮƽV_MOTORֱ
-* @return null
-*/
-void DecRsvFrameNum(uint8_t motorNo);
///*ڽṹ鸳ֵⲿʹô˽ṹ*/
//CommuHwInfo_t GetMotorCommuBuffStr(uint8_t motorNo);
diff --git a/BSP/Driver/servoMotor/servoMotor.c b/BSP/Driver/servoMotor/servoMotor.c
index d94c2b3..ef7ee7a 100644
--- a/BSP/Driver/servoMotor/servoMotor.c
+++ b/BSP/Driver/servoMotor/servoMotor.c
@@ -16,40 +16,69 @@ static void MotorSwitchGpioCofig(void)
}
+static uint8_t g_writeOneRegBuff[WRITE_ONE_REG_BUFFNUM];//дĴصݺдȫһ£
+
+
/*
ӻַ Ĵַ Ĵַ ݸλ ݵλ crcУλ crcУλ
01H 06H 02H 00H 00H 01H 49H B2H
*/
+/**
+* @brief ŷٶģʽдĴ
+* @param motorNoдֱˮƽ
+* @param regAddrҪдļĴ
+* @param dataҪĴд
+* @return false:дʧܣǰDMAڷ
+*/
bool WriteMotorOneReg(uint8_t motorNo, uint16_t regAddr, uint16_t data)
{
- uint8_t frameBuff[8] = {0};
- uint8_t replyTemp[8];
+ uint8_t frameBuff[WRITE_ONE_REG_BUFFNUM] = {0};
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 ( motorNo == H_MOTOR )
{
- if ( frameBuff[i] != replyTemp[i] )
- {
- H_MOTOR_STOP;
- return false;
- }
+ frameBuff[0] = H_MOTOR_ADDR;//ڲһһģʽˮƽֱӻַ0x01̨Ҳչ
}
+ else
+ {
+ frameBuff[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;
}
-
+/**
+* @brief дĴɹ᷵һ֡дʽȫһµ
+* @param motorNoдֱˮƽ
+* @param userBuffշصݵ
+* @param lenյݳȣڴ˺ΪWRITE_ONE_REG_BUFFNUM
+* @return false:дݲһ
+*/
+bool MotorReplyForWrite(uint8_t motorNo, uint8_t* userBuff, uint8_t len)
+{
+ CommuRsvData(motorNo, userBuff, len);
+ for( uint8_t i = 0; i < len; i++ )
+ {
+ if ( userBuff[i] != g_writeOneRegBuff[i] )
+ {
+ memset(g_writeOneRegBuff, 0x00, len);
+ return false;
+ }
+ }
+ memset(g_writeOneRegBuff, 0x00, len);
+ return true;
+}
/**
@@ -67,14 +96,20 @@ void servoMotorInit(void)
CommuDrvInit();//ŷRS485ͨѶʼ
OSTimeDlyHMSM(0u, 0u, 0u, 500u);//ȴӲʼɹ
WriteMotorOneReg(H_MOTOR, H02_CONTR_MODE_SELEC, 0);//H0200,ѡٶģʽ
-
+ OSTimeDlyHMSM(0u, 0u, 0u, 5u);
+
WriteMotorOneReg(H_MOTOR, H04_DO1_FUNC_SELEC, 19);
-
+ OSTimeDlyHMSM(0u, 0u, 0u, 5u);
+
WriteMotorOneReg(H_MOTOR, H06_SPEED_COMMU_SET_VALUE, 100);//ٶΪ100rpm
-
+ OSTimeDlyHMSM(0u, 0u, 0u, 5u);
+
WriteMotorOneReg(H_MOTOR, H06_SPEED_UP_SLOPE_VALUE, 3000);//ٶ3000
-
+ OSTimeDlyHMSM(0u, 0u, 0u, 5u);
+
WriteMotorOneReg(H_MOTOR, H06_SPEED_DOWN_SLOPE_VALUE, 2000);//ٶ2000
-
- WriteMotorOneReg(H_MOTOR, H03_DI1_LOGICAL_SELEC, 1);//ֻˮƽ
+ OSTimeDlyHMSM(0u, 0u, 0u, 5u);
+
+ WriteMotorOneReg(H_MOTOR, H03_DI1_LOGICAL_SELEC, 1);//ֻˮƽ
+ OSTimeDlyHMSM(0u, 0u, 0u, 5u);
}
\ No newline at end of file
diff --git a/BSP/Driver/servoMotor/servoMotor.h b/BSP/Driver/servoMotor/servoMotor.h
index fcd0f10..e77d6cb 100644
--- a/BSP/Driver/servoMotor/servoMotor.h
+++ b/BSP/Driver/servoMotor/servoMotor.h
@@ -14,6 +14,8 @@
#define V_MOTOR_OPEN gpio_bit_set(GPIOE,GPIO_PIN_1) //ֱԴ
#define V_MOTOR_STOP gpio_bit_reset(GPIOE,GPIO_PIN_1) //ֱԴر
+#define H_MOTOR_ADDR 0x01//ˮƽַ
+#define V_MOTOR_ADDR 0x01//ֱַ
/*
********************************************************************************************************
*
@@ -24,6 +26,7 @@
#define WRITE_ONE_REG 0X06//дĴ
#define WRITE_MULT_CONSE_REG 0x10//дļĴ
+#define WRITE_ONE_REG_BUFFNUM 8//дĴֽ֡ڸ
/*
********************************************************************************************************
* Ĵ
@@ -49,12 +52,26 @@
#define H0C_COMMU_PARAM_EEPR_UPDATE 0X0C13//MODBUSͨѶдǷµ EEPROM1Ϊд
-/*
-ӻַ Ĵַ Ĵַ ݸλ ݵλ crcУλ crcУλ
- 01H 06H 02H 00H 00H 01H 49H B2H
+
+
+/**
+* @brief ŷٶģʽдĴ
+* @param motorNoдֱˮƽ
+* @param regAddrҪдļĴ
+* @param dataҪĴд
+* @return false:дʧܣǰDMAڷ
*/
bool 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);
+
/**
* @brief ŷʼ
* @param
diff --git a/PROJECT/OS2.ewp b/PROJECT/OS2.ewp
index 3441585..571960f 100644
--- a/PROJECT/OS2.ewp
+++ b/PROJECT/OS2.ewp
@@ -826,7 +826,7 @@