diff --git a/firmware/build/MDK/project.uvprojx b/firmware/build/MDK/project.uvprojx index a9fea35..de6aa6d 100644 --- a/firmware/build/MDK/project.uvprojx +++ b/firmware/build/MDK/project.uvprojx @@ -16,7 +16,7 @@ STM32F103C8 STMicroelectronics - Keil.STM32F1xx_DFP.2.2.0 + Keil.STM32F1xx_DFP.2.3.0 http://www.keil.com/pack/ IROM(0x08000000,0x10000) IRAM(0x20000000,0x5000) CPUTYPE("Cortex-M3") CLOCK(12000000) ELITTLE diff --git a/firmware/src/Driver/adc.c b/firmware/src/Driver/adc.c index f2ca308..3f7371c 100644 --- a/firmware/src/Driver/adc.c +++ b/firmware/src/Driver/adc.c @@ -25,7 +25,7 @@ void ADC_Config(void) ADC_InitTypeDef ADC_InitStructure; RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE); - + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_3; GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AIN; GPIO_Init(GPIOA, &GPIO_InitStructure); @@ -63,11 +63,8 @@ void ADC_Config(void) *******************************************************************************/ void ADC1_2_IRQHandler(void) { - static u8 i = 0, x = 0, y = 0; - if (ADC1->SR & ADC_FLAG_JEOC) { - // LED_GR = !LED_GR; ADC1->SR &= ~(ADC_FLAG_JEOC); Cur_ADC = (short int)ADC1->JDR1; Temp_ADC = (short int)ADC1->JDR2; diff --git a/firmware/src/Driver/can.c b/firmware/src/Driver/can.c index b4701b3..f293d19 100644 --- a/firmware/src/Driver/can.c +++ b/firmware/src/Driver/can.c @@ -8,8 +8,14 @@ * @attention *******************************************************************************/ /* Includes ------------------------------------------------------------------*/ -#include "adc.h" +#include "can.h" +#include "motor.h" /* Definition ----------------------------------------------------------------*/ +// can_message_t can_tx_message; +// can_message_t can_rx_message; +CanTxMsg TxMessage = {0}; +CanRxMsg RxMessage; + extern short int Cur_ADC; extern short int Temp_ADC; /* Functions -----------------------------------------------------------------*/ @@ -17,123 +23,123 @@ extern short int Temp_ADC; * @brief CAN1初始化 * @param None * @retval None - * @note None + * @note 波特率=APB1Clock/(1+CAN_BS1+CAN_BS2)/CAN_Prescaler *******************************************************************************/ -void CAN1_Config(u16 bound) +void CAN1_Config(void) { - u8 brp = 3000 / bound; + GPIO_InitTypeDef GPIO_InitStructure; + CAN_InitTypeDef CAN_InitStructure; + CAN_FilterInitTypeDef CAN_FilterInitStructure; - GPIO_InitTypeDef GPIO_InitStructure; - CAN_InitTypeDef CAN_InitStructure; - CAN_FilterInitTypeDef CAN_FilterInitStructure; + RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE); //使能PORTA时钟 - GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12; - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP; - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; - GPIO_Init(GPIOA, &GPIO_InitStructure); + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; + GPIO_Init(GPIOA, &GPIO_InitStructure); - GPIO_InitStructure.GPIO_Pin = GPIO_Pin_11; - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPU; - GPIO_Init(GPIOA, &GPIO_InitStructure); - //CAN单元设置 - CAN_InitStructure.CAN_TTCM = DISABLE; //ENABLE:时间触发通信模式 DISABLE:非时间触发通信模式 - CAN_InitStructure.CAN_ABOM = ENABLE; //软件自动离线管理 - CAN_InitStructure.CAN_AWUM = DISABLE; //ENABLE:监测到can消息退出休眠模式 DISABLE:清除CAN->MCR的SLEEP位退出休眠模式 - CAN_InitStructure.CAN_NART = DISABLE; //ENABLE:无论发送成功与否只法一次 DISABLE:发送不成功一直重发 - CAN_InitStructure.CAN_RFLM = DISABLE; //ENABLE:FIFO溢出后丢弃后面的报文 DISABLE:溢出后新的覆盖旧的 - CAN_InitStructure.CAN_TXFP = ENABLE; //ENABLE:优先级由请求顺序决定 DISABLE:优先级由报文标识符决定 - CAN_InitStructure.CAN_Mode = CAN_Mode_Normal; //模式设置 - CAN_InitStructure.CAN_SJW = CAN_SJW_1tq; //重新同步跳跃宽度(Tsjw)为tsjw+1个时间单位 CAN_SJW_1tq~CAN_SJW_4tq - CAN_InitStructure.CAN_BS1 = CAN_BS1_6tq; //Tbs1范围CAN_BS1_1tq ~ CAN_BS1_16tq - CAN_InitStructure.CAN_BS2 = CAN_BS2_5tq; //Tbs2范围CAN_BS2_1tq ~ CAN_BS2_8tq - CAN_InitStructure.CAN_Prescaler = brp; //分频系数(Fdiv)为brp+1 - CAN_Init(CAN1, &CAN_InitStructure); //初始化CAN1 + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_11; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPU; + GPIO_Init(GPIOA, &GPIO_InitStructure); - //配置过滤器 - CAN_FilterInitStructure.CAN_FilterNumber = 0; //过滤器0 - CAN_FilterInitStructure.CAN_FilterMode = CAN_FilterMode_IdMask; //标识符屏蔽位模式 - CAN_FilterInitStructure.CAN_FilterScale = CAN_FilterScale_32bit; //过滤器位宽32位 - CAN_FilterInitStructure.CAN_FilterIdHigh = 0x0000; //32位ID - CAN_FilterInitStructure.CAN_FilterIdLow = 0x0000; - CAN_FilterInitStructure.CAN_FilterMaskIdHigh = 0x0000; //32位MASK - CAN_FilterInitStructure.CAN_FilterMaskIdLow = 0x0000; - CAN_FilterInitStructure.CAN_FilterFIFOAssignment = CAN_Filter_FIFO0; //过滤器0关联到FIFO0 - CAN_FilterInitStructure.CAN_FilterActivation = ENABLE; //激活过滤器0 - CAN_FilterInit(&CAN_FilterInitStructure); //滤波器初始化 + RCC_APB1PeriphClockCmd(RCC_APB1Periph_CAN1, ENABLE); //使能CAN1时钟 + //CAN单元设置 + CAN_InitStructure.CAN_TTCM = DISABLE; //ENABLE:时间触发通信模式 DISABLE:非时间触发通信模式 + CAN_InitStructure.CAN_ABOM = ENABLE; //软件自动离线管理 + CAN_InitStructure.CAN_AWUM = DISABLE; //ENABLE:监测到can消息退出休眠模式 DISABLE:清除CAN->MCR的SLEEP位退出休眠模式 + CAN_InitStructure.CAN_NART = DISABLE; //ENABLE:无论发送成功与否只发一次 DISABLE:发送不成功一直重发 + CAN_InitStructure.CAN_RFLM = DISABLE; //ENABLE:FIFO溢出后丢弃后面的报文 DISABLE:溢出后新的覆盖旧的 + CAN_InitStructure.CAN_TXFP = ENABLE; //ENABLE:优先级由请求顺序决定 DISABLE:优先级由报文标识符决定 + CAN_InitStructure.CAN_Mode = CAN_Mode_Normal; //模式设置 + CAN_InitStructure.CAN_SJW = CAN_SJW_1tq; //重新同步跳跃宽度(Tsjw)为tsjw+1个时间单位 CAN_SJW_1tq~CAN_SJW_4tq + CAN_InitStructure.CAN_BS1 = CAN_BS1_6tq; //Tbs1范围CAN_BS1_1tq ~ CAN_BS1_16tq + CAN_InitStructure.CAN_BS2 = CAN_BS2_5tq; //Tbs2范围CAN_BS2_1tq ~ CAN_BS2_8tq + CAN_InitStructure.CAN_Prescaler = 6; //分频系数(Fdiv)为CAN_Prescaler+1 + CAN_Init(CAN1, &CAN_InitStructure); //初始化CAN1 - // Motor_Cmd(Addr_Left,DISABLE); - // Motor_Cmd(Addr_Right,DISABLE); - // delay_ms(20);//CAN命令包发送完成 - CAN_ITConfig(CAN1, CAN_IT_FMP0, ENABLE); //FIFO0消息挂号中断允许. + //配置过滤器 + CAN_FilterInitStructure.CAN_FilterNumber = 0; //过滤器0 + CAN_FilterInitStructure.CAN_FilterMode = CAN_FilterMode_IdMask; //标识符屏蔽位模式 + CAN_FilterInitStructure.CAN_FilterScale = CAN_FilterScale_32bit; //过滤器位宽32位 + CAN_FilterInitStructure.CAN_FilterIdHigh = 0x0000; //32位ID + CAN_FilterInitStructure.CAN_FilterIdLow = 0x0000; + CAN_FilterInitStructure.CAN_FilterMaskIdHigh = 0x0000; //32位MASK + CAN_FilterInitStructure.CAN_FilterMaskIdLow = 0x0000; + CAN_FilterInitStructure.CAN_FilterFIFOAssignment = CAN_Filter_FIFO0; //过滤器0关联到FIFO0 + CAN_FilterInitStructure.CAN_FilterActivation = ENABLE; //激活过滤器0 + CAN_FilterInit(&CAN_FilterInitStructure); //滤波器初始化 + +#ifdef CAN_RX0_INT_ENABLE + NVIC_InitTypeDef NVIC_InitStructure; + NVIC_InitStructure.NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn; + NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1; // 主优先级为1 + NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; // 次优先级为0 + NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; + NVIC_Init(&NVIC_InitStructure); + + CAN_ITConfig(CAN1, CAN_IT_FMP0, ENABLE); //FIFO0消息挂号中断允许. +#endif } +#ifdef CAN_RX0_INT_ENABLE /******************************************************************************* * @brief CAN1中断 * @param None * @retval None * @note 速度模式s顺时针n逆时针 定位模式S顺时针N逆时针 *******************************************************************************/ -CanRxMsg BLcanbuf; -FlagStatus BL_Deal_Flag = RESET; void USB_LP_CAN1_RX0_IRQHandler(void) { - CanRxMsg RxMessagebuf; - CAN_Receive(CAN1, CAN_FIFO0, &RxMessagebuf); - // CanRx_TimeOut_Cnt = 3000; //500ms - - if (RxMessagebuf.StdId == 0x7df) + CAN_Receive(CAN1, CAN_FIFO0, &RxMessage); + if (RxMessage.StdId == 0x7df) + { + u16 speed = (RxMessage.Data[6] << 8) | RxMessage.Data[7]; + motor_set_speed(speed); + if (motor_info.state != MOTOR_STATE_RUNNING) { - // if ((RxMessagebuf.Data[0] == 'S') || (RxMessagebuf.Data[0] == 'P') || (RxMessagebuf.Data[0] == 'X') || (RxMessagebuf.Data[0] == 'D')) - // { - // Com_No_T1 = RxMessagebuf.Data[7]; - // if (Com_No_T1 != Com_No_OLD_T1) - // { - // if (RecDone_T1 == RESET) - // RecDone_T1 = SET; - // else - // return; - // memcpy(&uComRx_T1, RxMessagebuf.Data, 8); - // Com_No_OLD_T1 = Com_No_T1; - // } - // else - // { - // if (Say_Hello_T1 == 0) - // Say_Hello_T1 = 1; - // else - // return; - // uComTx_T1.mode = RxMessagebuf.Data[0]; - // } - // } + // motor_start(); } + } +} +#endif + +/******************************************************************************* + * @brief can发送消息 + * @param None + * @retval None + * @note None +*******************************************************************************/ +u8 can_send_message(u32 id, u8 dlc, u8 *data) +{ + u8 i; + u8 mbox; + u32 timeout = 0xffff; + TxMessage.StdId = id; // 标准标识符 + TxMessage.ExtId = id; // 设置扩展标示符 + TxMessage.IDE = 0; // 标准帧 + TxMessage.RTR = 0; // 数据帧 + TxMessage.DLC = dlc; // 要发送的数据长度 + for (i = 0; i < dlc; i++) + { + TxMessage.Data[i] = data[i]; + } + + do + { + mbox = CAN_Transmit(CAN1, &TxMessage); + timeout--; + } while ((mbox == CAN_TxStatus_NoMailBox) && (timeout > 0)); + + while ((CAN_TransmitStatus(CAN1, mbox) != CAN_TxStatus_Ok) && (timeout > 0)) + ; + return 1; } -int CanTx_TimeOut_Cnt = 0; -/********************************************************************** -* Description : None -* Input : None -* Output : None -* Return : None -* Attention : None -**********************************************************************/ -u8 can_send_message(u8 index, u32 id, u8 dlc, u8 *data) +u8 can_receive_message(CanRxMsg *message) { - u8 mbox; - CanTxMsg TxMessage; - TxMessage.StdId = id; // 标准标识符 - TxMessage.ExtId = id; // 设置扩展标示符 - TxMessage.IDE = 0; // 标准帧 - TxMessage.RTR = 0; // 数据帧 - TxMessage.DLC = dlc; // 要发送的数据长度 - CanTx_TimeOut_Cnt = 50; //25ms - memcpy(TxMessage.Data, data, 8); - do - { - mbox = CAN_Transmit(CAN1, &TxMessage); - } while ((mbox == CAN_TxStatus_NoMailBox) && (CanTx_TimeOut_Cnt != 0)); - - while ((CAN_TransmitStatus(CAN1, mbox) != CAN_TxStatus_Ok) && (CanTx_TimeOut_Cnt != 0)) - ; - CanTx_TimeOut_Cnt = 0; - return 1; + if (CAN_MessagePending(CAN1, CAN_FIFO0) == 0) + return 0; //没有接收到数据,直接退出 + CAN_Receive(CAN1, CAN_FIFO0, message); //读取数据 + return message->DLC; } /*********************************END OF FILE**********************************/ diff --git a/firmware/src/Driver/hall.c b/firmware/src/Driver/hall.c index 923fa48..db1d63b 100644 --- a/firmware/src/Driver/hall.c +++ b/firmware/src/Driver/hall.c @@ -11,8 +11,9 @@ #include "hall.h" #include "motor.h" /* Definition ----------------------------------------------------------------*/ -/* Functions -----------------------------------------------------------------*/ +u32 hall_last_interval = 0; //记录上次霍尔触发间隔,即电机转动1/6圈所花费的时间 +/* Functions -----------------------------------------------------------------*/ /******************************************************************************* * @brief 霍尔传感器初始化 * @param None @@ -21,77 +22,85 @@ *******************************************************************************/ void HALL_Config(void) { - //端口初始化 - GPIO_InitTypeDef GPIO_InitStructure; - RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB, ENABLE); - GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1 | GPIO_Pin_2; // - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING; - GPIO_Init(GPIOA, &GPIO_InitStructure); + //端口初始化 + GPIO_InitTypeDef GPIO_InitStructure; + RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB, ENABLE); + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1 | GPIO_Pin_2; // + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING; + GPIO_Init(GPIOA, &GPIO_InitStructure); - //定时器初始化 - RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE); - TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure; - TIM_TimeBaseStructure.TIM_Prescaler = 71; - TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; - TIM_TimeBaseStructure.TIM_Period = 1000; - TIM_TimeBaseStructure.TIM_ClockDivision = 0; - TIM_TimeBaseStructure.TIM_RepetitionCounter = 0; - TIM_TimeBaseInit(TIM2, &TIM_TimeBaseStructure); + //定时器初始化 + RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE); + TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure; + TIM_TimeBaseStructure.TIM_Prescaler = 71; + TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; + TIM_TimeBaseStructure.TIM_Period = 10000; + TIM_TimeBaseStructure.TIM_ClockDivision = 0; + TIM_TimeBaseStructure.TIM_RepetitionCounter = 0; + TIM_TimeBaseInit(TIM2, &TIM_TimeBaseStructure); - //输入捕获 - TIM_ICInitTypeDef TIM_ICInitStructure; + //输入捕获 + TIM_ICInitTypeDef TIM_ICInitStructure; - TIM_ICInitStructure.TIM_Channel = TIM_Channel_1; //监听T1霍尔事件 - TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Rising; //捕获上升沿 - TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_TRC; - TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1; //捕获分频 - TIM_ICInitStructure.TIM_ICFilter = 0xF; //输入滤波 - TIM_ICInit(TIM2, &TIM_ICInitStructure); + TIM_ICInitStructure.TIM_Channel = TIM_Channel_1; //监听CH1霍尔事件 + TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Rising; //捕获上升沿 + TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_TRC; //选择IC1,IC2,IC3通道亦或捕获 + TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1; //捕获分频 + TIM_ICInitStructure.TIM_ICFilter = 0xF; //输入滤波 + TIM_ICInit(TIM2, &TIM_ICInitStructure); - //输出配置 - TIM_OCInitTypeDef TIM_OCInitStructure; + //输出配置 + TIM_OCInitTypeDef TIM_OCInitStructure; - TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM2; //PWM模式2 - TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Disable; - TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High; - TIM_OCInitStructure.TIM_Pulse = 1023; // 1 is no delay; 2000 = 7ms - TIM_OC2Init(TIM2, &TIM_OCInitStructure); + TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM2; //PWM模式2 + TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Disable; + TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High; + TIM_OCInitStructure.TIM_Pulse = 1023; // 1 is no delay; 2000 = 7ms + TIM_OC2Init(TIM2, &TIM_OCInitStructure); - TIM_SelectHallSensor(TIM2, ENABLE); //使能HALL接口 - TIM_SelectInputTrigger(TIM2, TIM_TS_TI1F_ED); //边沿触发 - TIM_SelectSlaveMode(TIM2, TIM_SlaveMode_Reset); //定时器从模式上升沿重置 + TIM_SelectHallSensor(TIM2, ENABLE); //使能HALL接口 + TIM_SelectInputTrigger(TIM2, TIM_TS_TI1F_ED); //边沿触发 + TIM_SelectSlaveMode(TIM2, TIM_SlaveMode_Reset); //定时器从模式上升沿重置 - TIM_SelectMasterSlaveMode(TIM2, TIM_MasterSlaveMode_Enable); //主从模式选择 + TIM_SelectMasterSlaveMode(TIM2, TIM_MasterSlaveMode_Enable); //主从模式选择 - TIM_ClearFlag(TIM2, TIM_FLAG_CC2); - TIM_SelectOutputTrigger(TIM2, TIM_TRGOSource_OC2Ref); + TIM_ClearFlag(TIM2, TIM_FLAG_CC2); + TIM_SelectOutputTrigger(TIM2, TIM_TRGOSource_OC2Ref); - TIM_ITConfig(TIM2, TIM_IT_CC1 | TIM_IT_CC2, ENABLE); - TIM_Cmd(TIM2, ENABLE); + TIM_ITConfig(TIM2, TIM_IT_CC1 | TIM_IT_CC2, ENABLE); + TIM_Cmd(TIM2, ENABLE); - // 此处抢占中断,霍尔中断有更高的优先级 - NVIC_InitTypeDef NVIC_InitStructure; - NVIC_InitStructure.NVIC_IRQChannel = TIM2_IRQn; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0x00; - NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1; - NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; - NVIC_Init(&NVIC_InitStructure); + // 此处抢占中断,霍尔中断有更高的优先级 + NVIC_InitTypeDef NVIC_InitStructure; + NVIC_InitStructure.NVIC_IRQChannel = TIM2_IRQn; + NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0x00; + NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1; + NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; + NVIC_Init(&NVIC_InitStructure); } +/******************************************************************************* + * @brief TIM2定时器中断 + * @param None + * @retval None + * @note None +*******************************************************************************/ void TIM2_IRQHandler(void) { - if (TIM_GetITStatus(TIM2, TIM_IT_CC1) != RESET) - { - TIM_ClearITPendingBit(TIM2, TIM_IT_CC1); - motor_info.hall_position = get_hall_position(); - motor_step(); - } - else if (TIM_GetITStatus(TIM2, TIM_IT_CC2) != RESET) - { - TIM_ClearITPendingBit(TIM2, TIM_IT_CC2); - //换相 - // pwm_Commute(hallpos); - } + //通道1捕获中断,霍尔中断 + if (TIM_GetITStatus(TIM2, TIM_IT_CC1) != RESET) + { + TIM_ClearITPendingBit(TIM2, TIM_IT_CC1); + motor_info.hall_position = hall_position_detect(); + motor_step(); + hall_last_interval = TIM2->CCR1; //获取电机实际速度(rps)=(TIM2时钟频率*TIM2->CCR1)/6,这里避免中断中复杂计算,只缓存了电机转1/6圈的时间 + TIM_SetCounter(TIM2, 0); + } + else if (TIM_GetITStatus(TIM2, TIM_IT_CC2) != RESET) + { + TIM_ClearITPendingBit(TIM2, TIM_IT_CC2); + } + //TODO:此处考虑TIM2溢出中断判断电机堵转 } /******************************************************************************* @@ -100,8 +109,8 @@ void TIM2_IRQHandler(void) * @retval None * @note 采用定时器4的捕获功能捕获霍尔信号变化 *******************************************************************************/ -int get_hall_position(void) +int hall_position_detect(void) { - return (GPIO_ReadInputData(GPIOA) & 0x0007); + return (GPIO_ReadInputData(GPIOA) & 0x0007); } /*********************************END OF FILE**********************************/ diff --git a/firmware/src/Driver/inc/can.h b/firmware/src/Driver/inc/can.h index 95c0ad5..6493b15 100644 --- a/firmware/src/Driver/inc/can.h +++ b/firmware/src/Driver/inc/can.h @@ -12,10 +12,25 @@ /* Includes ------------------------------------------------------------------*/ #include "stm32f10x_conf.h" /* Definition ----------------------------------------------------------------*/ +#define CAN_RX0_INT_ENABLE //使能CAN接收中断 + +typedef struct +{ + u32 id; + u8 dlc; + u8 extend; //0:标准帧 1:拓展帧 + u8 remote; //0:数据帧 1:远程帧 + u8 data[8]; +} can_message_t; /* Exported Functions --------------------------------------------------------*/ -void CAN1_Config(u16 bound); -u8 can_send_message(u8 index, u32 id, u8 dlc, u8 *data); +// extern can_message_t can_tx_message; +// extern can_message_t can_rx_message; +extern CanTxMsg TxMessage; +extern CanRxMsg RxMessage; + +void CAN1_Config(void); +u8 can_send_message(u32 id, u8 dlc, u8 *data); #endif /*********************************END OF FILE**********************************/ diff --git a/firmware/src/Driver/inc/hall.h b/firmware/src/Driver/inc/hall.h index 416ff84..e7afe04 100644 --- a/firmware/src/Driver/inc/hall.h +++ b/firmware/src/Driver/inc/hall.h @@ -14,8 +14,10 @@ /* Definition ----------------------------------------------------------------*/ /* Exported Functions --------------------------------------------------------*/ +extern u32 hall_last_interval; + void HALL_Config(void); -int get_hall_position(void); +int hall_position_detect(void); #endif /*********************************END OF FILE**********************************/ diff --git a/firmware/src/Driver/inc/led.h b/firmware/src/Driver/inc/led.h index 533216b..9c491c3 100644 --- a/firmware/src/Driver/inc/led.h +++ b/firmware/src/Driver/inc/led.h @@ -14,7 +14,7 @@ /* Definition ----------------------------------------------------------------*/ /* Exported Functions --------------------------------------------------------*/ -void LED_Config(); +void LED_Config(void); void LED_ON(uint8_t index); void LED_OFF(uint8_t index); diff --git a/firmware/src/Driver/inc/motor.h b/firmware/src/Driver/inc/motor.h index 1520f62..e43641a 100644 --- a/firmware/src/Driver/inc/motor.h +++ b/firmware/src/Driver/inc/motor.h @@ -12,6 +12,8 @@ /* Includes ------------------------------------------------------------------*/ #include "stm32f10x_conf.h" /* Definition ----------------------------------------------------------------*/ +#define MOTOR_TRANSMITTING_RATIO 58 + enum motor_mode { MOTOR_MODE_SPEED, //速度模式 @@ -27,7 +29,9 @@ enum motor_dir enum motor_state { - MOTOR_STATE_STOP //停止状态 + MOTOR_STATE_STOP, //停止状态 + MOTOR_STATE_RUNNING, //运行状态 + MOTOR_STATE_ERROR, //故障状态 }; typedef struct _motor @@ -36,8 +40,8 @@ typedef struct _motor u8 dir; u8 state; //运行状态 u8 hall_position; //霍尔位置 - s16 speed; //转速 - u32 step; + float speed; //转速(r/min) + s32 step; } motor_t; diff --git a/firmware/src/Driver/led.c b/firmware/src/Driver/led.c index 98851fb..7ab468a 100644 --- a/firmware/src/Driver/led.c +++ b/firmware/src/Driver/led.c @@ -18,7 +18,7 @@ * @retval None * @note None *******************************************************************************/ -void LED_Config() +void LED_Config(void) { GPIO_InitTypeDef GPIO_InitStructure; RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE); @@ -39,12 +39,12 @@ void LED_ON(uint8_t index) { if (index == 0) { - GPIO_WriteBit(GPIOB, GPIO_Pin_5, SET); + GPIO_WriteBit(GPIOB, GPIO_Pin_5, Bit_SET); } if (index == 1) { - GPIO_WriteBit(GPIOB, GPIO_Pin_6, SET); + GPIO_WriteBit(GPIOB, GPIO_Pin_6, Bit_SET); } } @@ -58,12 +58,12 @@ void LED_OFF(uint8_t index) { if (index == 0) { - GPIO_WriteBit(GPIOB, GPIO_Pin_5, RESET); + GPIO_WriteBit(GPIOB, GPIO_Pin_5, Bit_RESET); } if (index == 1) { - GPIO_WriteBit(GPIOB, GPIO_Pin_6, RESET); + GPIO_WriteBit(GPIOB, GPIO_Pin_6, Bit_RESET); } } /*********************************END OF FILE**********************************/ diff --git a/firmware/src/Driver/motor.c b/firmware/src/Driver/motor.c index f247080..2508027 100644 --- a/firmware/src/Driver/motor.c +++ b/firmware/src/Driver/motor.c @@ -9,9 +9,21 @@ *******************************************************************************/ /* Includes ------------------------------------------------------------------*/ #include "motor.h" +#include "hall.h" /* Definition ----------------------------------------------------------------*/ motor_t motor_info; /* Functions -----------------------------------------------------------------*/ +/******************************************************************************* + * @brief 电机驱动MOS管输出 + * @param None + * @retval None + * @note None +*******************************************************************************/ +void motor_mos_enable(FunctionalState state) +{ + GPIO_WriteBit(GPIOB, GPIO_Pin_12, state); //关闭MOS输出 +} + /******************************************************************************* * @brief 电机初始化 * @param None @@ -25,8 +37,7 @@ void motor_init(void) GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP; GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; GPIO_Init(GPIOB, &GPIO_InitStructure); - GPIO_WriteBit(GPIOB, GPIO_Pin_12, RESET); //关闭MOS输出 - motor_info.dir = MOTOR_DIR_CCW; + } /******************************************************************************* @@ -37,10 +48,10 @@ void motor_init(void) *******************************************************************************/ void motor_start(void) { - motor_info.state = 1; - GPIO_WriteBit(GPIOB, GPIO_Pin_12, SET); + motor_info.state = MOTOR_STATE_RUNNING; + motor_mos_enable(ENABLE); //TODO:开启霍尔捕捉中断 - motor_info.hall_position = get_hall_position(); + motor_info.hall_position = hall_position_detect(); motor_step(); } @@ -53,6 +64,8 @@ void motor_start(void) void motor_stop(void) { motor_info.state = MOTOR_STATE_STOP; + hall_last_interval = 0; + motor_mos_enable(DISABLE); TIM1->CCR1 = 0; TIM1->CCR2 = 0; TIM1->CCR3 = 0; @@ -140,8 +153,9 @@ void motor_step(void) break; default: motor_stop(); - break; + return; } + motor_info.dir == MOTOR_DIR_CCW ? motor_info.step-- : motor_info.step++; TIM_GenerateEvent(TIM1, TIM_EventSource_COM); } @@ -153,9 +167,16 @@ void motor_step(void) *******************************************************************************/ void motor_set_speed(s16 speed) { + if (speed == 0) + { + motor_stop(); + return; + } + TIM1->CCR1 = speed; TIM1->CCR2 = speed; TIM1->CCR3 = speed; + motor_start(); } /*********************************END OF FILE**********************************/ diff --git a/firmware/src/Driver/pwm.c b/firmware/src/Driver/pwm.c index 7bb00e1..c592d8a 100644 --- a/firmware/src/Driver/pwm.c +++ b/firmware/src/Driver/pwm.c @@ -39,16 +39,9 @@ void PWM_Config(void) GPIO_ResetBits(GPIOB, GPIO_Pin_13); GPIO_ResetBits(GPIOB, GPIO_Pin_14); GPIO_ResetBits(GPIOB, GPIO_Pin_15); - // GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12; - // GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP; - // GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; - // GPIO_Init(GPIOB, &GPIO_InitStructure); - // GPIO_SetBits(GPIOB, GPIO_Pin_12); - - //PWM频率:12k TIM_DeInit(TIM1); - + //PWM频率:12k TIM_TimeBaseStructure.TIM_Prescaler = 1; //2分频 TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_CenterAligned2; //中央对齐计数模式,输出比较标志位只有在比较器向上计算被设置 TIM_TimeBaseStructure.TIM_Period = 1500 - 1; //PWM频率计算:72000000/TIM_Period+1/TIM_Prescaler+1,如果是中央对齐计数模式再除以2 @@ -56,13 +49,13 @@ void PWM_Config(void) TIM_TimeBaseStructure.TIM_RepetitionCounter = 0; TIM_TimeBaseInit(TIM1, &TIM_TimeBaseStructure); - TIM_OCInitStructure.TIM_OCMode = TIM_ForcedAction_InActive; //PWM2:递增计数时CNTCCRx,OC输出有效电平 TIM_ForcedAction_InActive + TIM_OCInitStructure.TIM_OCMode = TIM_ForcedAction_InActive; //默认初始化为无效电平 TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable; TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Enable; - TIM_OCInitStructure.TIM_Pulse = 0; - TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High; + TIM_OCInitStructure.TIM_Pulse = 0; //默认占空比0 + TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High; //起始波形为高电平 TIM_OCInitStructure.TIM_OCNPolarity = TIM_OCPolarity_High; - TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Reset; //TIM_OCIdleState_Set;TIM_OCIdleState_Reset + TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Reset; //空闲状态下输出低电平,仅TIM1,TIM8有效 TIM_OCInitStructure.TIM_OCNIdleState = TIM_OCIdleState_Reset; TIM_OC1Init(TIM1, &TIM_OCInitStructure); TIM_OC2Init(TIM1, &TIM_OCInitStructure); @@ -79,7 +72,7 @@ void PWM_Config(void) TIM_BDTRInitStructure.TIM_OSSIState = TIM_OSSIState_Enable; TIM_BDTRInitStructure.TIM_LOCKLevel = TIM_LOCKLevel_1; TIM_BDTRInitStructure.TIM_DeadTime = 100; - TIM_BDTRInitStructure.TIM_Break = TIM_Break_Disable; //如打开,开机无输出且状态紊乱???? + TIM_BDTRInitStructure.TIM_Break = TIM_Break_Disable; TIM_BDTRInitStructure.TIM_BreakPolarity = TIM_BreakPolarity_Low; TIM_BDTRInitStructure.TIM_AutomaticOutput = TIM_AutomaticOutput_Disable; TIM_BDTRConfig(TIM1, &TIM_BDTRInitStructure); @@ -89,18 +82,12 @@ void PWM_Config(void) TIM_OC3PreloadConfig(TIM1, TIM_OCPreload_Enable); //使能捕获比较寄存器预装载(通道3) TIM_OC4PreloadConfig(TIM1, TIM_OCPreload_Enable); //使能捕获比较寄存器预装载(通道4) - TIM_SelectInputTrigger(TIM1, TIM_TS_ITR1); //输入触发源选择内部触发3:ITR3(TIM1->TIM4,TIM8->TIM5) - - TIM_CCPreloadControl(TIM1, ENABLE); //CCER预装载 - - TIM_SelectCOM(TIM1, ENABLE); //软件触发和TRGI触发更新 - - TIM_CtrlPWMOutputs(TIM1, ENABLE); - + TIM_SelectInputTrigger(TIM1, TIM_TS_ITR1); //输入触发源选择内部触发 + TIM_CCPreloadControl(TIM1, ENABLE); //CCER预装载 + TIM_SelectCOM(TIM1, ENABLE); //软件触发和TRGI触发更新 + TIM_CtrlPWMOutputs(TIM1, ENABLE); //使能PWM输出 TIM_ClearITPendingBit(TIM1, TIM_IT_COM); - TIM_ITConfig(TIM1, TIM_IT_COM, ENABLE); //开启COM中断,意图:6路互补PWM设置被更改后不是立即生效,需要等待其它关联定时器触发更改,或者通过COM中断来立即执行更改 - TIM_Cmd(TIM1, ENABLE); } diff --git a/firmware/src/User/inc/main.h b/firmware/src/User/inc/main.h index 88a0e5a..c76344d 100644 --- a/firmware/src/User/inc/main.h +++ b/firmware/src/User/inc/main.h @@ -15,6 +15,7 @@ #include "led.h" #include "hall.h" #include "pwm.h" +#include "can.h" #include "motor.h" /* Definition ----------------------------------------------------------------*/ diff --git a/firmware/src/User/main.c b/firmware/src/User/main.c index 9960bc9..3a9b0b4 100644 --- a/firmware/src/User/main.c +++ b/firmware/src/User/main.c @@ -34,7 +34,6 @@ void RCC_Config() *******************************************************************************/ void test(void) { - motor_init(); motor_start(); delay_ms(5000); motor_set_speed(100); @@ -84,16 +83,23 @@ int main(void) NVIC_Config(); GPIO_PinRemapConfig(GPIO_Remap_SWJ_JTAGDisable, ENABLE); //关闭jtag,保留swd。 SysTick_init(); + LED_Config(); HALL_Config(); PWM_Config(); CAN1_Config(); - test(); + motor_init(); + + // test(); while (1) { - LED_ON(1); - delay_ms(500); - LED_OFF(1); delay_ms(500); + TxMessage.StdId = 0x111; + TxMessage.DLC = 8; + TxMessage.Data[0] = motor_info.state; + motor_info.speed = 1000000.0f * 60 / (hall_last_interval * 6 * MOTOR_TRANSMITTING_RATIO); + TxMessage.Data[6] = (u32)motor_info.speed >> 8; + TxMessage.Data[7] = (u32)motor_info.speed; + CAN_Transmit(CAN1, &TxMessage); } }