/******************** (C) COPYRIGHT 2023 GeekRebot ***************************** * File Name : moto.c * Current Version : V1.0 & ST 3.5.0 * Author : zhanli 719901725@qq.com * Date of Issued : 2023.04.06 zhanli: Create * Comments : 直流减速电机控制 ********************************************************************************/ #include "moto.h" #include "bsp_sys.h" /**---------------------------------------------------------------------- 硬件连接说明: // 电机控制 PB0 -> R_PWM PB13-> R_IN2 PB12-> R_IN1 PB1 -> L_PWM PB14-> L_IN2 PB15-> L_IN1 PA0 -> LA PA1 -> LB // 编码器 // 左电机编码器计数 PA0----接 编码器A相 或者电机驱动的B2B标识 PA1----接 编码器B相 或者电机驱动的B2A标识 // 右电机编码器计数 PB6----接 编码器B相 或者电机驱动的B1A标识 PB7----接 编码器A相 或者电机驱动的B1B标识 TB6612驱动中, 小车车头对应前进方向, Left对应A,Right对应B *---------------------------------------------------------------------**/ //PWM在timer3里配置 void MOTO_GPIO_Init(void) { GPIO_InitTypeDef GPIO_InitStructure; RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE); /*开启GPIO的外设时钟*/ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12 | GPIO_Pin_13 | GPIO_Pin_14 | GPIO_Pin_15; /*选择要控制的GPIO引脚*/ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP; /*设置引脚模式为通用推挽输出*/ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; /*设置引脚速率为50MHz */ GPIO_Init(GPIOB, &GPIO_InitStructure); /*调用库函数,初始化GPIO*/ } //左电机 void MOTO_Left(char state) { if(state == GO)//左前电机前进 { GPIO_SetBits(GPIOB,GPIO_Pin_12); GPIO_SetBits(GPIOB,GPIO_Pin_14); GPIO_SetBits(GPIOB,GPIO_Pin_15); TIM3->CCR4=1500; } if(state == BACK)//左前电机后退 { GPIO_ResetBits(GPIOB,GPIO_Pin_12); GPIO_ResetBits(GPIOB,GPIO_Pin_14); GPIO_ResetBits(GPIOB,GPIO_Pin_15); TIM3->CCR4=1500; } if(state == STOP)//停转 { TIM3->CCR4=0; //更新pwm } } //右电机 void MOTO_Right(char state) { if(state == GO)//左前电机前进 { GPIO_SetBits(GPIOB,GPIO_Pin_13); TIM3->CCR3=1500; //更新pwm } if(state == BACK)//左前电机后退 { GPIO_ResetBits(GPIOB,GPIO_Pin_13); TIM3->CCR3=1500; //更新pwm } if(state == STOP)//停转 { TIM3->CCR3=0; //更新pwm } } //***************************前进***************************// //只要配置()的状态就可以改变电机转动方向 void Car_Go(void) { //左电机 前 //右电机 前 MOTO_Left(GO); MOTO_Right(GO); } void Car_Back(void) { //左电机 后 //右电机 后 MOTO_Left(BACK); MOTO_Right(BACK); } //***************************向左转圈***************************// void Car_Turn_Left(void) { //左电机 后 //右电机 前 MOTO_Left(BACK); MOTO_Right(GO); } //***************************向右转圈***************************// void Car_Turn_Right(void) { //左电机 前 //右电机 后 MOTO_Left(GO); MOTO_Right(BACK); } //***************************停车***************************// void Car_Stop(void) { MOTO_Left(STOP); MOTO_Right(STOP); }