ROS小车STM32底板代码学习

用的是幻尔科技的新推出的ROS小车的STM32控制底板价格

他的代码是用HAL库写的,而且资料很少,刚开始连ROS1功能包都还在测试。

代码有300多M,编译一次,直接吃席。所以我用轮趣科技的ROS小车代码移植,采用的FreeRTOS写的,跟我学的代码风格几乎一致

移植过程中你会发现,电路很多地方都一致,盲猜有抄板。

注意:幻尔科技的没有电位器,无法通过改变电位器电平来改变车型。所以我在代码中直接固定了车型,手头电机有限,就选择差速小车。只需要两个轮子。

他这边的车型选择将ADC电平分段表示的注释掉,直接选择3号差速。OLED那边也是一样直接定死。

void Robot_Select(void)
{

//	Divisor_Mode=2048/CAR_NUMBER+5;
//	Car_Mode=(int) ((Get_adc_Average(Potentiometer,10))/Divisor_Mode); //Collect the pin information of potentiometer //²É¼¯µçλÆ÷Òý½ÅÐÅÏ¢	
//  if(Car_Mode>5)Car_Mode=5;

	Car_Mode=3;
	
	switch(Car_Mode)
	{
		case Mec_Car:       Robot_Init(MEC_wheelspacing,         MEC_axlespacing,          0,                     HALL_30F, Hall_13, Mecanum_75);            break; //Âó¿ËÄÉÄ·ÂÖС³µ
		case Omni_Car:      Robot_Init(0,                        0,                        Omni_Turn_Radiaus_109, HALL_30F, Hall_13, FullDirecion_60);       break; //È«ÏòÂÖС³µ
		case Akm_Car:       Robot_Init(Akm_wheelspacing,         Akm_axlespacing,          0,                     HALL_30F, Hall_13, Black_WheelDiameter);   break; //°¢¿ËÂüС³µ
		case Diff_Car:      Robot_Init(Diff_wheelSpacing,        0,                        0,                     HALL_30F, Hall_13, Black_WheelDiameter);   break; //Á½ÂÖ²îËÙС³µ
		case FourWheel_Car: Robot_Init(Four_Mortor_wheelSpacing, Four_Mortor__axlespacing, 0,                     HALL_30F, Hall_13, Black_WheelDiameter);   break; //ËÄÇý³µ 
		case Tank_Car:      Robot_Init(Tank_wheelSpacing,        0,                        0,                     HALL_30F, Hall_13, Tank_WheelDiameter);    break; //ÂÄ´ø³µ
	}

在system.c里面也有定义。可以统一定所有的mode

u8 Car_Mode=3;
// Robot type variable
//机器人型号变量
//0=Mec_Car,1=Omni_Car,2=Akm_Car,3=Diff_Car,4=FourWheel_Car,5=Tank_Car

 现在出现问题,在下载好我修改过后的代码后(还有按键、灯,OLED显示我都修改过了。)

差速小车模式。轮趣代码的AB电机对应这边24电机。

这边仔细对比了一下原理图,发现电机驱动器和编码器的对应有不同的地方,需要在编码器代码的初始化部分修改。(已修改,用蓝牙控制差速小车的两个电机正常。用ROS键盘控制今天有点问题,估计也是对应的问题。)

在修改编码器和电机驱动器的代码的时候,我有一些困扰,后来只按照电路表改了编码器的接口。

现在总结一下,motor.c就是电机驱动器,用两个PWN信号控制电机转速的。encoder.c就是编码器,他只是给外部编码器点击一个接口,同时通过时钟信号能够计算编码器传出来的转速。

总结:motor.c用来控制电机,encoder.c用来计算电机转速。


目前已经移植完毕,现在系统的顺一遍代码的流程。

首先看主函数main.c:

#include "system.h"

//Task priority    //任务优先级
#define START_TASK_PRIO	1

//Task stack size //任务堆栈大小	
#define START_STK_SIZE 	256  

//Task handle     //任务句柄
TaskHandle_t StartTask_Handler;

//Task function   //任务函数
void start_task(void *pvParameters);

//Main function //主函数
int main(void)
{ 
  systemInit(); //Hardware initialization //硬件初始化
	
	//Create the start task //创建开始任务
	xTaskCreate((TaskFunction_t )start_task,            //Task function   //任务函数
							(const char*    )"start_task",          //Task name       //任务名称
							(uint16_t       )START_STK_SIZE,        //Task stack size //任务堆栈大小
							(void*          )NULL,                  //Arguments passed to the task function //传递给任务函数的参数
							(UBaseType_t    )START_TASK_PRIO,       //Task priority   //任务优先级
							(TaskHandle_t*  )&StartTask_Handler);   //Task handle     //任务句柄    					
	vTaskStartScheduler();  //Enables task scheduling //开启任务调度	
}
 
//Start task task function //开始任务任务函数
void start_task(void *pvParameters)
{
    taskENTER_CRITICAL(); //Enter the critical area //进入临界区
	
    //Create the task //创建任务
   	xTaskCreate(Balance_task,  "Balance_task",  BALANCE_STK_SIZE,  NULL, BALANCE_TASK_PRIO,  NULL);	//Vehicle motion control task //小车运动控制任务
	xTaskCreate(MPU6050_task, "MPU6050_task", MPU6050_STK_SIZE, NULL, MPU6050_TASK_PRIO, NULL);	//IMU data read task //IMU数据读取任务 
    xTaskCreate(show_task,     "show_task",     SHOW_STK_SIZE,     NULL, SHOW_TASK_PRIO,     NULL); //The OLED display displays tasks //OLED显示屏显示任务
    xTaskCreate(led_task,      "led_task",      LED_STK_SIZE,      NULL, LED_TASK_PRIO,      NULL);	//LED light flashing task //LED灯闪烁任务
    xTaskCreate(pstwo_task,    "PSTWO_task",    PS2_STK_SIZE,      NULL, PS2_TASK_PRIO,      NULL);	//Read the PS2 controller task //读取PS2手柄任务
    xTaskCreate(data_task,     "DATA_task",     DATA_STK_SIZE,     NULL, DATA_TASK_PRIO,     NULL);	//Usartx3, Usartx1 and CAN send data task //串口3、串口1、CAN发送数据任务
	
    vTaskDelete(StartTask_Handler); //Delete the start task //删除开始任务

    taskEXIT_CRITICAL();            //Exit the critical section//退出临界区
}

 这边的FreeRTOS的代码跟正点原子的代码风格很像,所以看的比幻尔科技的亲切很多。

system.h是system.c的头文件中定义了很多函数头文件和函数初始化以及参数的定义。放在统一的文件中,方便所有文件使用,不需要一个一个的对应添加了。

systemInit()硬件初始化在system.c文件中定义,包括各种硬件外设的初始化等。

接下来就是各种任务的创建,他们的6个任务的优先级和堆栈大小任务函数都在各自的函数文件中定义。

这边都没定义任务句柄,也就是不存在挂起和恢复的操作。



看电机相关的编码器和电机驱动的函数encoder.c和motor.c

void Encoder_Init_TIM2(void)
{
	TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;  
  TIM_ICInitTypeDef TIM_ICInitStructure;  
  GPIO_InitTypeDef GPIO_InitStructure;
	
  RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE);   //使能定时器
  RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOA|RCC_AHB1Periph_GPIOB, ENABLE);  //使用A B口
 
  GPIO_InitStructure.GPIO_Pin = GPIO_Pin_15;  //PA15
  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_100MHz;
  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
  GPIO_InitStructure.GPIO_OType = GPIO_OType_OD;
  GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
  GPIO_Init(GPIOA, &GPIO_InitStructure);  
	
	GPIO_InitStructure.GPIO_Pin = GPIO_Pin_3;  //PB3
  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_100MHz;
  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
  GPIO_InitStructure.GPIO_OType = GPIO_OType_OD;
  GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
  GPIO_Init(GPIOB, &GPIO_InitStructure);  

  GPIO_PinAFConfig(GPIOA,GPIO_PinSource15,GPIO_AF_TIM2);   //复用为TIM2 编码器接口
  GPIO_PinAFConfig(GPIOB,GPIO_PinSource3,GPIO_AF_TIM2);   //复用为TIM2 编码器接口
  
  TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
  
  TIM_TimeBaseStructure.TIM_Prescaler = 0x0; 							// No prescaling     //不分频
  TIM_TimeBaseStructure.TIM_Period = ENCODER_TIM_PERIOD;  //设定计数器自动重装值
  TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1; //选择时钟分频:不分频
  TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; //TIM向上计数    
  TIM_TimeBaseInit(TIM2, &TIM_TimeBaseStructure);  //初始化定时器
  
  TIM_EncoderInterfaceConfig(TIM2, TIM_EncoderMode_TI12, TIM_ICPolarity_Rising, TIM_ICPolarity_Rising);//使用编码器模式3
  TIM_ICStructInit(&TIM_ICInitStructure);
  TIM_ICInitStructure.TIM_ICFilter = 0;
  TIM_ICInit(TIM2, &TIM_ICInitStructure);
  
  TIM_ClearFlag(TIM2, TIM_FLAG_Update);//清除TIM的更新标志位
  TIM_ITConfig(TIM2, TIM_IT_Update, ENABLE);
  TIM_SetCounter(TIM2,0);
  TIM_Cmd(TIM2, ENABLE); 
}

int Read_Encoder(u8 TIMX)
{
 int Encoder_TIM;    
 switch(TIMX)
 {
	case 2:  Encoder_TIM= (short)TIM2 -> CNT;   TIM2 -> CNT=0;  break;
	case 3:  Encoder_TIM= (short)TIM3 -> CNT;   TIM3 -> CNT=0;  break;
	case 4:  Encoder_TIM= (short)TIM4 -> CNT;   TIM4 -> CNT=0;  break;	
	case 5:  Encoder_TIM= (short)TIM5 -> CNT;   TIM5 -> CNT=0;  break;	
	default: Encoder_TIM=0;
 }
	return Encoder_TIM;
}

void TIM2_IRQHandler(void)
{ 		    		  			    
	if(TIM2->SR&0X0001) //Overflow interrupt //溢出中断
	{    				   				     	    	
	}				   
	TIM2->SR&=~(1<<0); //Clear the interrupt flag bit //清除中断标志位 	    
}

这是encoder.c代码,我只截取其中一个定时器和读取和终端程序(太长了)

这边是增量式编码器(正交编码器),通过两个信号线的脉冲输出来处理,一个输出脉冲信号就对应一个增量位移,编码器每转动固定的位移,就会产生一个脉冲信号,读取单位脉冲信号的数量,就可以达到测速效果,v=S/t。通过对脉冲信号的累加和编码器的码盘的周长(转一圈距离)就可以达到行走距离效果(S=n*d)

编码器信号: 

A 脉冲输出 

B 脉冲输出 

Z 零点信号 当编码器旋转到零点时,Z信号会发出一个脉冲表示现在是零位置 表示编码器转了1圈,可用来记录编码器转了多少圈,从而知道运行距离

VCC 电源线

GND 地线

编码器线数:

编码器的线数 ,是说编码器转一圈输出多少个脉冲,如果一个编码器是500线,说明这个编码器转一圈对应的信号线会输出500个脉冲, A B两相转一圈发出的脉冲数一样的,不过存在90°相位差。线数越大代表编码器能够反映的位置精度越高

编码器原理:

增量式编码器有两个脉冲输出,A相和B相,并且两个相位永远存在90°相位差。 如果两个信号相位差为90度,则这两个信号称为正交。由于两个信号相差90度,因此可以根据两个信号哪个先哪个后来判断方向、并且可以根据AB相脉冲信号数量测得速度,位移等

这边我自己的理解:想象成没刹车的自行车(靠踏板制动甚至倒退)的两个踏板,永远是相差180°,以最下面为Z点,两侧踏板每过一次,算各自的一圈。假设右踏板为A,左踏板为B。假设开始保持两个踏板跟地面平行。那么向前的时候,A踏板先过Z,超前B180°,制动并后退的时候,B逆时针过Z,超前A180°。单位时间过Z的次数可以计算速度和距离(需要轮子周长)

正转的时候信号线A先输出信号,信号线B后输出  A相超前B相90度  是正转

反转的时候信号线B先输出信号,信号线A后输出 B相超前A相90度 是反转

 

下图是STM32中文手册里面编码器接口模式的介绍定义

这边内容有点多,从别的博主那里截取几张图当理解。一共三个编码器模式。

TIM_EncoderInterfaceConfig(TIM2, TIM_EncoderMode_TI12, TIM_ICPolarity_Rising, TIM_ICPolarity_Rising);

TIMx参数就是使用哪个定时器作为编码器接口的捕捉定时器。

TIM_EncoderMode参数是模式,是单相计数(仅在TL1计数或仅在TL2计数)还是两相计数(在TL1和TL2都计数)。

TIM_IC1Polarity和TIM_IC2Polarity参数就是通道1、2的捕捉极性。(TIM_EncoderInterfaceConfig函数的后两个参数命名为TIM_ICPolarity_Rising实际使用的是反相和不反相的功能

程序中通过对CNT计数的读取,获取编码器数值(原始数据)。

 读取编码器的函数在计算电机速度的时候使用。在计算balance.c文件中的Get_Velocity_Form_Encoder()函数里面。其中

MOTOR_A.Encoder= Encoder_A_pr*CONTROL_FREQUENCY*Wheel_perimeter/Encoder_precision;函数我详细的计算了一遍。其实最终就是速度公式。


motor.c的程序

void TIM9_PWM_Init(u16 arr,u16 psc)
{
TIM_TimeBaseInitTypeDef TIM_TimeBaseInitStructure;
GPIO_InitTypeDef GPIO_InitStructure;
TIM_OCInitTypeDef TIM_OCInitStructure;

RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM9,ENABLE);/*使能定时器11时钟*/
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOE,ENABLE);/*使能GPIOF时钟*/

GPIO_PinAFConfig(GPIOE,GPIO_PinSource5,GPIO_AF_TIM9);/*复用*/
GPIO_PinAFConfig(GPIOE,GPIO_PinSource6,GPIO_AF_TIM9);/*复用*/

GPIO_InitStructure.GPIO_Pin = GPIO_Pin_5|GPIO_Pin_6;           //GPIOF9
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;        //复用功能
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_100MHz;	//速度100MHz
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;      //推挽复用输出
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;        //上拉
GPIO_Init(GPIOE,&GPIO_InitStructure);              //初始化PF9

TIM_TimeBaseInitStructure.TIM_Period = arr;/*自动重装载*/
TIM_TimeBaseInitStructure.TIM_Prescaler = psc;/*预分频*/
TIM_TimeBaseInitStructure.TIM_ClockDivision = TIM_CKD_DIV1;/*时钟分频*/
TIM_TimeBaseInitStructure.TIM_CounterMode = TIM_CounterMode_Up;/*向上计数*/
TIM_TimeBaseInit(TIM9,&TIM_TimeBaseInitStructure);/*初始化*/

TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;/*PWM模式*/
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;/*输出*/
TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High;/*比较极性高*/
TIM_OC1Init(TIM9,&TIM_OCInitStructure);
TIM_OC2Init(TIM9,&TIM_OCInitStructure);

TIM_OC1PreloadConfig(TIM9,TIM_OCPreload_Enable);/*输出比较预装载使能*/
TIM_OC2PreloadConfig(TIM9,TIM_OCPreload_Enable);/*输出比较预装载使能*/

TIM_ARRPreloadConfig(TIM9,ENABLE);/*自动重载预装载使能*/

TIM_Cmd(TIM9,ENABLE);/*计数使能*/

}

只截取其中一段PWM的初始化设置。可以看到这边的arr自动重装载值和预分频都是PWM配置参数。PWM模式1。输出PWM

通过计数时候对比CNT和CRR的值(在重装载值之内),判断高低电平。

TIM_OCPolarity这个参数比较极性高的意思是高电平有效。

Tout = ((arr+1)*(psc+1))/Tclk

这个公式就是计算一次重装载时间的计数时间T,倒数就是频率F。

Tclk是定时器时钟源,不是72MHz,看下图从正点原子里面截取的一张时钟图和两段文字介绍。

下图是在stm32里面的定义system_stm32f4xx.c文件里面。可以看到APB2的预分频系数为2.

根据上面所说,不为1的话就是APB域的频率的两倍。而APB2为84MHz,所以定时器时钟频率为84*2=168MHz

所以APB2时钟频率(不是域的频率)为168M,满PWM为16799,频率=168M/((16799+1)*(0+1))=10k。

PWM的输出频率为10KHZ,用来控制电机速度。PWM频率是指1秒钟内信号从高电平到低电平再回到高电平的次数(一个周期)


在motor.c里面定义的#define PWMA1       TIM10->CCR1,

捕获/比较寄存器TIMx_CCR1~4

在输出模式下,该寄存器的值与 CNT 的值比较,根据比较结果产生相应动作。利用这点,我们通过修改这个寄存器的值,就可以控制 PWM 的输出脉宽了。

在balance.c里面有个控制PWM输出控制前进后退的代码:

void Set_Pwm(int motor_a,int motor_b,int motor_c,int motor_d,int servo)
{
	//Forward and reverse control of motor
	//电机正反转控制
	if(motor_a<0)			PWMA1=16799,PWMA2=16799+motor_a;
	else 	            PWMA2=16799,PWMA1=16799-motor_a;
	
	//Forward and reverse control of motor
	//电机正反转控制	
	if(motor_b<0)			PWMB1=16799,PWMB2=16799+motor_b;
	else 	            PWMB2=16799,PWMB1=16799-motor_b;
}

截取前两个,这边看到因为AB两个轮子是相对放置,所以前后转应该相反,事实也是如此。定义的时候已经定义好

这边只看PWMA1和PWMA2控制,因为FI控制前进输入,BI控制后退输入。所以前进就是FI高电平输出,BI低电平输出。然后FO前进输出就是高电平,就可以前进了。



2023.9.2号,板子烧了,很奇怪,之前还好好的。(只有串口CH9102烧了,查不出原因,按道理只有短接会这样,但我都是架高的)

同时也翻了个错误,在航模遥控的定时器初始化那边,对于TIM8高级定时器的初始化,我将与轮趣不一样的引脚直接改成幻尔的定义,但是原本高级定时器TIM8的通道1-4就是PC6-9

我按照电路图直接修改了PC6-7为PA11-12。

那么原本的幻尔上板子的PC67是总线舵机的使用的三台输出模块的输入接口。这边就得好好琢磨一下。

在代码中,原本通道1和通道2也就是PC67是。CH1控制右摇杆(左右推,控制差速自转)。CH2控制左摇杆(前后控制前进后退)

如果板子修好后,继续能用,直接将原先的前进差速改成CH34来捕获。差速只需要这两个就行了。(暂时这么想,等板子回来,修不好的话,自己画或者直接买轮趣的了)


板子花100块修好了,继续之前的话题!!

也就是说观察代码,CH1和CH2两个通道控制前进后退,CH3控制油门(这个我感觉很奇怪)

发现了,CH3在代码中有个定义

在remote_control函数中,也就是航模控制的代码。其中

Remote_RCvelocity=RC_Velocity+RX;就是对油门的控制,其中RC_Velocity是小车默认速度500mm/s

RX是通道3设定的获取油门。

猜想:只需要通道1和通道2,就可以完成小车的前进后退,左右,速度是一个均值(由于幻尔的板子上得舵机这边的引脚和轮趣的差异不小,先这么尝试先)

幻尔这边,没有PC6和PC7在舵机这边用,被集成到芯片引脚上去了。所以只能使用PC8和PC9当前后左右了

也就是将原来CH1和CH2的活转到CH3和CH4上面。

11.1号移植成功,但是问题没有解决,摇杆归零速度不停,保持原来的速度,而且继续推杆会增加速度。(怀疑输入捕获的摇杆的推量被转换成了加速度,且在累加)

准备先测试一下航模接收机的信号(示波器,看看是不是正常方波信号的高电平变化)

void Remote_Control(void)
{
	  //Data within 1 second after entering the model control mode will not be processed
	  //对进入航模控制模式后1秒内的数据不处理
    static u8 thrice=100; 
    int Threshold=100; //Threshold to ignore small movements of the joystick //阈值,忽略摇杆小幅度动作

	  //limiter //限幅
    int LX,LY,RY,RX,Remote_RCvelocity; 
		Remoter_Ch1=target_limit_int(Remoter_Ch1,1000,2000);
		Remoter_Ch2=target_limit_int(Remoter_Ch2,1000,2000);
		Remoter_Ch3=target_limit_int(Remoter_Ch3,1000,2000);
		Remoter_Ch4=target_limit_int(Remoter_Ch4,1000,2000);

	  // Front and back direction of left rocker. Control forward and backward.
	  //左摇杆前后方向。控制前进后退。
    LX=Remoter_Ch2-1500; 
	
	  //Left joystick left and right.Control left and right movement. Only the wheelie omnidirectional wheelie will use the channel.
	  //Ackerman trolleys use this channel as a PWM output to control the steering gear
	  //左摇杆左右方向。控制左右移动。麦轮全向轮才会使用到改通道。阿克曼小车使用该通道作为PWM输出控制舵机
    LY=Remoter_Ch4-1500;

    //Front and back direction of right rocker. Throttle/acceleration/deceleration.
		//右摇杆前后方向。油门/加减速。
	  RX=Remoter_Ch3-1500;

    //Right stick left and right. To control the rotation. 
		//右摇杆左右方向。控制自转。
    RY=Remoter_Ch1-1500; 

    if(LX>-Threshold&&LX<Threshold)LX=0;
    if(LY>-Threshold&&LY<Threshold)LY=0;
    if(RX>-Threshold&&RX<Threshold)RX=0;
	  if(RY>-Threshold&&RY<Threshold)RY=0;
		
		//Throttle related //油门相关
		Remote_RCvelocity=RC_Velocity+RX;
	  if(Remote_RCvelocity<0)Remote_RCvelocity=0;
		
		//The remote control command of model aircraft is processed
		//对航模遥控控制命令进行处理
    Move_X= LX*Remote_RCvelocity/500; 
		Move_Y=-LY*Remote_RCvelocity/500;
		Move_Z=-RY*(PI/2)/500;      
			 
		//Z轴数据转化
	  if(Car_Mode==Mec_Car||Car_Mode==Omni_Car)
		{
			Move_Z=Move_Z*Remote_RCvelocity/500;
		}	
		else if(Car_Mode==Akm_Car)
		{
			//Ackermann structure car is converted to the front wheel steering Angle system target value, and kinematics analysis is pearformed
		  //阿克曼结构小车转换为前轮转向角度
			Move_Z=Move_Z*2/9;
		}
		else if(Car_Mode==Diff_Car||Car_Mode==Tank_Car||Car_Mode==FourWheel_Car)
		{
			if(Move_X<0) Move_Z=-Move_Z; //The differential control principle series requires this treatment //差速控制原理系列需要此处理
			Move_Z=Move_Z*Remote_RCvelocity/500;
		}
		
	  //Unit conversion, mm/s -> m/s
    //单位转换,mm/s -> m/s	
		Move_X=Move_X/1000;       
    Move_Y=Move_Y/1000;      
		Move_Z=Move_Z;
		
	  //Data within 1 second after entering the model control mode will not be processed
	  //对进入航模控制模式后1秒内的数据不处理
    if(thrice>0) Move_X=0,Move_Z=0,thrice--;
				
		//Control target value is obtained and kinematics analysis is performed
	  //得到控制目标值,进行运动学分析
		Drive_Motor(Move_X,Move_Y,Move_Z);
}

已成功,PID开环控制的问题,因为编码器没有检测到实际速度,导致PID闭环控制一直跟0速度比较,属于是开环起飞了。编码器上边的代码有问题,TIM2对应的引脚就是之前的代码,我擅自改了。

定时器引脚对应的通道是固定的。(傻了)。

posted @ 2023-08-22 18:08  祈愿树下  阅读(365)  评论(0编辑  收藏  举报
// 侧边栏目录 // https://blog-static.cnblogs.com/files/douzujun/marvin.nav.my1502.css