STM32HAL库电机开发-三环控制-位置式PID-有刷减速电机

承接上文,我们分别实现了速度环、电流环、位置环的控制,我们接下来讲解三环控制,三环控制使得电机控制精度更高,其中电流环为最内环,其次是速度环,最外圈是位置环。

代码讲解

相对于单独的单环控制来说多环控制的工程包括了所有,编码器电流检测,其中的pid.c文件中的pid计算变成了三份,初始化了三套pid算法。如图
s
在每次的pid代码中添加了限制闭环死区和积分分离方舟跑偏。
在这里插入图片描述
闭环死区是指执行机构的最小控制量,无法再通过调节来满足控制精度,如果仍然持续调节,系统则会在目标值前后频繁动作,不能稳定下来。

比如某个系统的控制精度是1,但目标值需要是1.5,则无论怎么调节,最终的结果只能控制在 1或 2,始终无法达到预设值。这 1.5L小数点后的范围,就是闭环死区,系统是无法控制的,误差会一直存在,容易发生震荡现象。
积分分离的设定
通过积分分离的方式来实现抗积分饱和,积分饱和是指执行机构达到极限输出能力了,仍无法到达目标值,在很长一段时间内无法消除静差造成的。

例如,PWM输出到了100%,仍达不到期望位置,此时若一直进行误差累加,在一段时间后, PID 的积分项累计了很大的数值,如果这时候到达了目标值或者重新设定了目标值,由于积分由于累计的误差很大,系统并不能立即调整到目标值,可能造成超调或失调的现象。
主函数没有太大的变化:
在这里插入图片描述
其中pid的调控开始是在基本定时器的定时中断回调开始的。
在这里插入图片描述
接下来是最重要的代码在代码运行中实现多环控制:代码流程是位置环三次周期一运行,而速度环两次周期,电流环每次都运行
其中位置环或者速度环计算完成后将返回值设置为下一环的目标值,最后由电流环值进行控制。

void motor_pid_control(void)
{
  static uint32_t louter_ring_timer = 0;      // 外环环周期(电流环计算周期为定时器周期T,速度环为2T,位置环为3T)
  int32_t actual_current = get_curr_val();    // 读取当前电流值
  if(actual_current > TARGET_CURRENT_MAX)
  {
	  actual_current = TARGET_CURRENT_MAX;
  }
  if (is_motor_en == 1)                  // 电机在使能状态下才进行控制处理
  {
    static int32_t Capture_Count = 0;    // 当前时刻总计数值
    static int32_t Last_Count = 0;       // 上一时刻总计数值
    float cont_val = 0;                  // 当前控制值
    
    /* 当前时刻总计数值 = 计数器值 + 计数溢出次数 * ENCODER_TIM_PERIOD  */
    Capture_Count = __HAL_TIM_GET_COUNTER(&TIM_EncoderHandle) + (Encoder_Overflow_Count * ENCODER_TIM_PERIOD);
    
    /* 位置环计算 */
    if (louter_ring_timer++ % 3 == 0)
    {
      cont_val = location_pid_realize(&pid_location, Capture_Count);    // 进行 PID 计算

      /* 目标速度上限处理 */
      if (cont_val > TARGET_SPEED_MAX)
      {
        cont_val = TARGET_SPEED_MAX;
      }
      else if (cont_val < -TARGET_SPEED_MAX)
      {
        cont_val = -TARGET_SPEED_MAX;
      }
   
      set_pid_target(&pid_speed, cont_val);    // 位置环中返回的值设定定速度环的目标值
      
    #if defined(PID_ASSISTANT_EN)
      int32_t temp = cont_val;
      set_computer_value(SEND_TARGET_CMD, CURVES_CH2, &temp, 1);     // 给通道 2 发送目标值
    #endif
    }

    /* 速度环计算 */
    static int32_t actual_speed = 0;                 // 实际测得速度
    if (louter_ring_timer % 2 == 0)
    {
      /* 转轴转速 = 单位时间内的计数值 / 编码器总分辨率 * 时间系数  */
      actual_speed = ((float)(Capture_Count - Last_Count) / ENCODER_TOTAL_RESOLUTION / REDUCTION_RATIO) / (GET_BASIC_TIM_PERIOD()*2/1000.0/60.0);
        
      /* 记录当前总计数值,供下一时刻计算使用 */
      Last_Count = Capture_Count;
      
      cont_val = speed_pid_realize(&pid_speed, actual_speed);    // 进行 PID 计算

      if (cont_val > 0)    // 判断电机方向
      {
        set_motor_direction(MOTOR_FWD);
      }
      else
      {
        cont_val = -cont_val;
        set_motor_direction(MOTOR_REV);
      }
   
      cont_val = (cont_val > TARGET_CURRENT_MAX) ? TARGET_CURRENT_MAX : cont_val;    // 电流上限处理
      set_pid_target(&pid_curr, cont_val);    // 速度环结束后的值设定为电流环的目标值
      
    #if defined(PID_ASSISTANT_EN)
      int32_t temp = cont_val;
      set_computer_value(SEND_TARGET_CMD, CURVES_CH3, &temp, 1);     // 给通道 3 发送目标值  
    #endif
    }
    
    /* 电流环计算 */
    cont_val = curr_pid_realize(&pid_curr, actual_current);    // 实际是控制电流改变速度,要设定电流环初始目标值。
    
    if (cont_val < 0)
    {
      cont_val = 0;    // 下限处理
    }
    else if (cont_val > PWM_MAX_PERIOD_COUNT)
    {
      cont_val = PWM_MAX_PERIOD_COUNT;    // 速度上限处理
    }

    set_motor_speed(cont_val);                                                 // 设置 PWM 占空比
    
  #if defined(PID_ASSISTANT_EN)
    set_computer_value(SEND_FACT_CMD, CURVES_CH1, &Capture_Count,  1);         // 给通道 1 发送实际值
//    set_computer_value(SEND_FACT_CMD, CURVES_CH2, &actual_speed,   1);         // 给通道 2 发送实际值
//    set_computer_value(SEND_FACT_CMD, CURVES_CH3, &actual_current, 1);         // 给通道 3 发送实际值
  #else
    printf("1.电流:实际值:%d. 目标值:%.0f.\n", Capture_Count, get_pid_target(&pid_location));      // 打印实际值和目标值
  #endif
  }
}

在进行pid参数调整时,先调电流环,把其他环注释掉,得到理想结果再跳速度环,再调位置环。

  • 4
    点赞
  • 34
    收藏
    觉得还不错? 一键收藏
  • 4
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论 4
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值