【ST电机MCLib 生成文件比较】

本文围绕ST电机MCLib生成文件展开,对比了6step不同工作模式下文章差异,包括头文件和源文件。详细解析了hall_speed_pos_fdbk.c文件,涉及api、硬件接口定义等内容。还介绍了API调用情况,如init mc_task.c mcboot()等,为STM32电机控制开发提供参考。

摘要生成于 C知道 ,由 DeepSeek-R1 满血版支持, 前往体验 >

ST电机MCLib 生成文件比较

参考文章:STM32 PMSM SDK 5.2 training
ST电机库v5.4.4源代码分析(4): 电角度和力矩方向分析(Hall传感器)
speed unit 和 dpp 解释

一、6step不同工作模式下文章的差异

有三种选择,hall传感器。encode传感器,状态观察传感器。

1。头文件比较

  1. hall与encoder
    在这里插入图片描述
    hall传感器里多了hall_speed_pos_fdbk.h.
    有差异的文件是
    driver_parameters.h,
    main.h,
    mc_config.h,
    mc_configuration_registers.h,
    parameters_conversion.h

  2. hall与观察传感器

在这里插入图片描述
不同的文件与 1 相同。

2。源文件比较

  1. hall与encoder比较
    在这里插入图片描述
    不同的文件如下:
    hall多一个文件: hall_speed_pos_fdbk.c
    不同的文件为:
    main.c
    mc_config.c
    mc_task.c
    register_interface.c
    stm32g4xx_hal_msp.c
    stm32g4xx_mc_it,c

  2. hall与observer比较
    在这里插入图片描述
    不同的文件与上述相同.

二、hall_speed_pos_fdbk.c解析

1。api

void HALL_Init(HALL_Handle_t *pHandle);
void HALL_Clear(HALL_Handle_t *pHandle);

void *HALL_TIMx_UP_IRQHandler(void *pHandleVoid);
void *HALL_TIMx_CC_IRQHandler(void *pHandleVoid);

int16_t HALL_CalcElAngle(HALL_Handle_t *pHandle);
bool HALL_CalcAvrgMecSpeedUnit(HALL_Handle_t *pHandle, int16_t *hMecSpeedUnit);

void HALL_Init(HALL_Handle_t *pHandle):
It initializes the hardware peripherals (TIMx, GPIO and NVIC)
required for the speed position sensor management using HALL
sensors.

2。硬件接口定义:

uint32_t TIMClockFreq;
TIM_TypeDef *TIMx;
uint32_t H1Pin; used,
GPIO_TypeDef *H2Port;
uint32_t ICx_Filter;

3。stm32xxx.h中定义的一些寄存器直接操作及原子操作:

/** @addtogroup Exported_macros
  * @{
  */
#define SET_BIT(REG, BIT)     ((REG) |= (BIT))

#define CLEAR_BIT(REG, BIT)   ((REG) &= ~(BIT))

#define READ_BIT(REG, BIT)    ((REG) & (BIT))

#define CLEAR_REG(REG)        ((REG) = (0x0))

#define WRITE_REG(REG, VAL)   ((REG) = (VAL))

#define READ_REG(REG)         ((REG))

#define MODIFY_REG(REG, CLEARMASK, SETMASK)  WRITE_REG((REG), (((READ_REG(REG)) & (~(CLEARMASK))) | (SETMASK)))

#define POSITION_VAL(VAL)     (__CLZ(__RBIT(VAL)))

/* Use of CMSIS compiler intrinsics for register exclusive access */
/* Atomic 32-bit register access macro to set one or several bits */
#define ATOMIC_SET_BIT(REG, BIT)                             \
  do {                                                       \
    uint32_t val;                                            \
    do {                                                     \
      val = __LDREXW((__IO uint32_t *)&(REG)) | (BIT);       \
    } while ((__STREXW(val,(__IO uint32_t *)&(REG))) != 0U); \
  } while(0)

/* Atomic 32-bit register access macro to clear one or several bits */
#define ATOMIC_CLEAR_BIT(REG, BIT)                           \
  do {                                                       \
    uint32_t val;                                            \
    do {                                                     \
      val = __LDREXW((__IO uint32_t *)&(REG)) & ~(BIT);      \
    } while ((__STREXW(val,(__IO uint32_t *)&(REG))) != 0U); \
  } while(0)

/* Atomic 32-bit register access macro to clear and set one or several bits */
#define ATOMIC_MODIFY_REG(REG, CLEARMSK, SETMASK)                          \
  do {                                                                     \
    uint32_t val;                                                          \
    do {                                                                   \
      val = (__LDREXW((__IO uint32_t *)&(REG)) & ~(CLEARMSK)) | (SETMASK); \
    } while ((__STREXW(val,(__IO uint32_t *)&(REG))) != 0U);               \
  } while(0)

/* Atomic 16-bit register access macro to set one or several bits */
#define ATOMIC_SETH_BIT(REG, BIT)                            \
  do {                                                       \
    uint16_t val;                                            \
    do {                                                     \
      val = __LDREXH((__IO uint16_t *)&(REG)) | (BIT);       \
    } while ((__STREXH(val,(__IO uint16_t *)&(REG))) != 0U); \
  } while(0)

/* Atomic 16-bit register access macro to clear one or several bits */
#define ATOMIC_CLEARH_BIT(REG, BIT)                          \
  do {                                                       \
    uint16_t val;                                            \
    do {                                                     \
      val = __LDREXH((__IO uint16_t *)&(REG)) & ~(BIT);      \
    } while ((__STREXH(val,(__IO uint16_t *)&(REG))) != 0U); \
  } while(0)

/* Atomic 16-bit register access macro to clear and set one or several bits */
#define ATOMIC_MODIFYH_REG(REG, CLEARMSK, SETMASK)                         \
  do {                                                                     \
    uint16_t val;                                                          \
    do {                                                                   \
      val = (__LDREXH((__IO uint16_t *)&(REG)) & ~(CLEARMSK)) | (SETMASK); \
    } while ((__STREXH(val,(__IO uint16_t *)&(REG))) != 0U);               \
  } while(0)

4。hall信号超时设置:HallTimeOut定义:

   /* SW Init */
   if (0U == hMinReliableElSpeedUnit)  //未定义
   {
     /* Set fixed to 150 ms */
     pHandle->HallTimeout = 150U;
   }
   else
   {
     /* Set accordingly the min reliable speed */
     /* 1000 comes from mS
     * 6 comes from the fact that sensors are toggling each 60 deg = 360/6 deg */
     pHandle->HallTimeout = (1000U * (uint16_t)SPEED_UNIT) / (6U * hMinReliableElSpeedUnit);
   }
   hMinReliableElSpeedUnit的单位应该为(digit/ms),
   #define SPEED_UNIT U_01HZ
   #define U_01HZ 10
   乘以1000,是变成us?
   hMeasurementFrequency
   SpeedSamplingFreqHz
   pHandle->PWMNbrPSamplingFreq = ((pHandle->_Super.hMeasurementFrequency * pHandle->PWMFreqScaling) /
                                   pHandle->SpeedSamplingFreqHz) - 1U;

定时器参数的自适应处理:

    LL_TIM_IC_SetFilter(TIMx, LL_TIM_CHANNEL_CH1, (uint32_t)(pHandle->ICx_Filter) << 20U);//滤波器
    LL_TIM_SetPrescaler(TIMx, pHandle->HALLMaxRatio);//根据最低速度需求,设置预分频
    LL_TIM_GenerateEvent_UPDATE(TIMx);
     /* Clear the TIMx's pending flags */
    WRITE_REG(TIMx->SR, 0);

    /* Selected input capture and Update (overflow) events generate interrupt */

    /* Source of Update event is only counter overflow/underflow */
    LL_TIM_SetUpdateSource(TIMx, LL_TIM_UPDATESOURCE_COUNTER);

    LL_TIM_EnableIT_CC1(TIMx);
    LL_TIM_EnableIT_UPDATE(TIMx);
    LL_TIM_SetCounter(TIMx, HALL_COUNTER_RESET);

    LL_TIM_CC_EnableChannel(TIMx, LL_TIM_CHANNEL_CH1);
    LL_TIM_EnableCounter(TIMx);
    只是允许了一个通道的中断?

5. 测速初始化:HALL_Clear()

主要是执行 HALL_Init_Electrical_Angle(pHandle);
获得转子的初始位置。

6。速度极低,hall变化超时 HALL_TIMx_UP_IRQHandler

7。速度及方向计算 HALL_TIMx_CC_IRQHandler

  • 根据霍尔状态,设定转子角度dpp,即360度为65536。状态4为0,5为60度。

  • speed unit 设置为0.1hz,当函数返回0.1hz的300时,RPM则为300/10(转化为秒)*60=1800r/min

  • STM32 FOC SDK2.0中使用hall传感器获取电角度的公式解析
    Wdpp = CKTIM * 2^16/(captured value * prescaler value) /(3* SAMPLING_FREQ)
    转/s: CKTIM /(captured value * prescaler value) /(3)
    转/每采样周期(pwm) : CKTIM /(captured value * prescaler value) /(3* SAMPLING_FREQ)
    每圏为2Π,360度,dpp值为216,所以Wdpp如上。

  • speed unit/01Hz速度转为Wdpp:
    W1hz = W01hz /10
    Wdpp = W01hz /10 /Focsample * 216;

  .DPPConvFactor             = DPP_CONV_FACTOR,
  #define DPP_CONV_FACTOR                        (65536 / PWM_FREQ_SCALING)
pHandle->PseudoFreqConv = ((pHandle->TIMClockFreq / 6U) / pHandle->_Super.hMeasurementFrequency)
                              * pHandle->_Super.DPPConvFactor;
pHandle->AvrElSpeedDpp = (int16_t)((int32_t)pHandle->PseudoFreqConv /
                 (pHandle->ElPeriodSum / (int32_t)pHandle->SpeedBufferSize)); /* Average value */cc中断中计算速度
 转/s:         (pHandle->TIMClockFreq / 6U)    /  (pHandle->ElPeriodSum / (int32_t)pHandle->SpeedBufferSize));
 转/每采样周期:     xx/  pHandle->_Super.hMeasurementFrequency
 转成W~dpp~   xx*   pHandle->_Super.DPPConvFactor;;                                    
  • Wdpp 转化为Wspeedunit(01hz)
 /* Convert el_dpp to MecUnit */
  *hMecSpeedUnit = (int16_t)((pHandle->AvrElSpeedDpp * (int32_t)pHandle->_Super.hMeasurementFrequency
                        * (int32_t)SPEED_UNIT )
                        / ((int32_t)(pHandle->_Super.DPPConvFactor) * (int32_t)(pHandle->_Super.bElToMecRatio)) );
   转化W~01hz~: (int16_t)((pHandle->AvrElSpeedDpp * (int32_t)pHandle->_Super.hMeasurementFrequency
                        * (int32_t)SPEED_UNIT )
                        / ((int32_t)(pHandle->_Super.DPPConvFactor) 
  电子角转化为机械角: x/  (int32_t)(pHandle->_Super.bElToMecRatio)
                    

8。计算机械转速speedunit HALL_CalcAvrgMecSpeedUnit

9。计算电子转速dpp HALL_CalcElAngle

三、API调用

1. init mc_task.c mcboot():

HALL:


   HALL_Init (&HALL_M1);

    /******************************************************/
    /*   Speed & torque component initialization          */
    /******************************************************/
    STC_Init(pSTC[M1],&PIDSpeedHandle_M1, &HALL_M1._Super);

Encoder:

 /******************************************************/
    /*   Main speed sensor component initialization       */
    /******************************************************/
    ENC_Init (&ENCODER_M1);

    /******************************************************/
    /*   Main encoder alignment component initialization  */
    /******************************************************/
    EAC_Init(&EncAlignCtrlM1,pSTC[M1],&VirtualSpeedSensorM1,&ENCODER_M1);
    pEAC[M1] = &EncAlignCtrlM1;

    /******************************************************/
    /*   Speed & torque component initialization          */
    /******************************************************/
    STC_Init(pSTC[M1],&PIDSpeedHandle_M1, &ENCODER_M1._Super);

    /****************************************************/
    /*   Virtual speed sensor component initialization  */
    /****************************************************/
    VSS_Init(&VirtualSpeedSensorM1);

observe:

 /******************************************************/
    /*   Main speed sensor component initialization       */
    /******************************************************/
    STO_PLL_Init (&STO_PLL_M1);

    /******************************************************/
    /*   Speed & torque component initialization          */
    /******************************************************/
    STC_Init(pSTC[M1],&PIDSpeedHandle_M1, &STO_PLL_M1._Super);

    /****************************************************/
    /*   Virtual speed sensor component initialization  */
    /****************************************************/
    VSS_Init(&VirtualSpeedSensorM1);

    /**************************************/
    /*   Rev-up component initialization  */
    /**************************************/
    RUC_Init(&RevUpControlM1, pSTC[M1], &VirtualSpeedSensorM1, &STO_M1, pwmcHandle[M1]);

2. HALL_Clear()

mc_task.c TSK_MediumFrequencyTaskM1
Hall:

            if (TSK_ChargeBootCapDelayHasElapsedM1())
            {
              R3_1_SwitchOffPWM(pwmcHandle[M1]);
              HALL_Clear(&HALL_M1);
              FOC_Clear( M1 );

              FOC_InitAdditionalMethods(M1);
              FOC_CalcCurrRef(M1);
              STC_ForceSpeedReferenceToCurrentSpeed( pSTC[M1]); /* Init the reference speed to current speed */
              MCI_ExecBufferedCommands(&Mci[M1]); /* Exec the speed ramp after changing of the speed sensor */
              Mci[M1].State = RUN;
              PWMC_SwitchOnPWM(pwmcHandle[M1]);
            }

encoder:

case CHARGE_BOOT_CAP:
        {
          if (MCI_STOP == Mci[M1].DirectCommand)
          {
            TSK_MF_StopProcessing(M1);
          }
          else
          {
            if (TSK_ChargeBootCapDelayHasElapsedM1())
            {
              R3_1_SwitchOffPWM(pwmcHandle[M1]);
              FOCVars[M1].bDriveInput = EXTERNAL;
              STC_SetSpeedSensor( pSTC[M1], &VirtualSpeedSensorM1._Super );
              ENC_Clear(&ENCODER_M1);
              FOC_Clear( M1 );

              if (EAC_IsAligned(&EncAlignCtrlM1) == false)
              {
                EAC_StartAlignment(&EncAlignCtrlM1);
                Mci[M1].State = ALIGNMENT;
              }
              else
              {
                STC_SetControlMode(pSTC[M1], MCM_SPEED_MODE);
                STC_SetSpeedSensor(pSTC[M1], &ENCODER_M1._Super);
                FOC_InitAdditionalMethods(M1);
                FOC_CalcCurrRef(M1);
                STC_ForceSpeedReferenceToCurrentSpeed(pSTC[M1]); /* Init the reference speed to current speed */
                MCI_ExecBufferedCommands(&Mci[M1]); /* Exec the speed ramp after changing of the speed sensor */
                Mci[M1].State = RUN;
              }
              PWMC_SwitchOnPWM(pwmcHandle[M1]);
            }
            else
            {
              /* Nothing to be done, FW waits for bootstrap capacitor to charge */
            }
          }
          break;
        }

        case ALIGNMENT:
        {
          if (MCI_STOP == Mci[M1].DirectCommand)
          {
            TSK_MF_StopProcessing(M1);
          }
          else
          {
            bool isAligned = EAC_IsAligned(&EncAlignCtrlM1);
            bool EACDone = EAC_Exec(&EncAlignCtrlM1);
            if ((isAligned == false)  && (EACDone == false))
            {
              qd_t IqdRef;
              IqdRef.q = 0;
              IqdRef.d = STC_CalcTorqueReference(pSTC[M1]);
              FOCVars[M1].Iqdref = IqdRef;
            }
            else
            {
              R3_1_SwitchOffPWM( pwmcHandle[M1] );
              STC_SetControlMode(pSTC[M1], MCM_SPEED_MODE);
              STC_SetSpeedSensor(pSTC[M1], &ENCODER_M1._Super);
              FOC_Clear(M1);
              R3_1_TurnOnLowSides(pwmcHandle[M1],M1_CHARGE_BOOT_CAP_DUTY_CYCLES);
              TSK_SetStopPermanencyTimeM1(STOPPERMANENCY_TICKS);
              Mci[M1].State = WAIT_STOP_MOTOR;
              /* USER CODE BEGIN MediumFrequencyTask M1 EndOfEncAlignment */

              /* USER CODE END MediumFrequencyTask M1 EndOfEncAlignment */
            }
          }
          break;
        }

observer:

case CHARGE_BOOT_CAP:
        {
          if (MCI_STOP == Mci[M1].DirectCommand)
          {
            TSK_MF_StopProcessing(M1);
          }
          else
          {
            if (TSK_ChargeBootCapDelayHasElapsedM1())
            {
              R3_1_SwitchOffPWM(pwmcHandle[M1]);
              FOCVars[M1].bDriveInput = EXTERNAL;
              STC_SetSpeedSensor( pSTC[M1], &VirtualSpeedSensorM1._Super );
              STO_PLL_Clear(&STO_PLL_M1);
              FOC_Clear( M1 );

                Mci[M1].State = START;
              PWMC_SwitchOnPWM(pwmcHandle[M1]);
            }
            else
            {
              /* Nothing to be done, FW waits for bootstrap capacitor to charge */
            }
          }
          break;
        }

        case START:
        {
          if (MCI_STOP == Mci[M1].DirectCommand)
          {
            TSK_MF_StopProcessing(M1);
          }
          else
          {
            /* Mechanical speed as imposed by the Virtual Speed Sensor during the Rev Up phase. */
            int16_t hForcedMecSpeedUnit;
            qd_t IqdRef;
            bool ObserverConverged;

            /* Execute the Rev Up procedure */
            if(! RUC_Exec(&RevUpControlM1))
            {
            /* The time allowed for the startup sequence has expired */
              MCI_FaultProcessing(&Mci[M1], MC_START_UP, 0);
            }
            else
            {
              /* Execute the torque open loop current start-up ramp:
               * Compute the Iq reference current as configured in the Rev Up sequence */
              IqdRef.q = STC_CalcTorqueReference(pSTC[M1]);
              IqdRef.d = FOCVars[M1].UserIdref;
              /* Iqd reference current used by the High Frequency Loop to generate the PWM output */
              FOCVars[M1].Iqdref = IqdRef;
           }

            (void)VSS_CalcAvrgMecSpeedUnit(&VirtualSpeedSensorM1, &hForcedMecSpeedUnit);

            /* Check that startup stage where the observer has to be used has been reached */
            if (true == RUC_FirstAccelerationStageReached(&RevUpControlM1))
            {
              ObserverConverged = STO_PLL_IsObserverConverged(&STO_PLL_M1, &hForcedMecSpeedUnit);
              STO_SetDirection(&STO_PLL_M1, (int8_t)MCI_GetImposedMotorDirection(&Mci[M1]));

              (void)VSS_SetStartTransition(&VirtualSpeedSensorM1, ObserverConverged);
            }
            else
            {
              ObserverConverged = false;
            }
            if (ObserverConverged)
            {
              qd_t StatorCurrent = MCM_Park(FOCVars[M1].Ialphabeta, SPD_GetElAngle(&STO_PLL_M1._Super));

              /* Start switch over ramp. This ramp will transition from the revup to the closed loop FOC */
              REMNG_Init(pREMNG[M1]);
              (void)REMNG_ExecRamp(pREMNG[M1], FOCVars[M1].Iqdref.q, 0);
              (void)REMNG_ExecRamp(pREMNG[M1], StatorCurrent.q, TRANSITION_DURATION);
              Mci[M1].State = SWITCH_OVER;
            }
          }
          break;
        }

        case SWITCH_OVER:
        {
          if (MCI_STOP == Mci[M1].DirectCommand)
          {
            TSK_MF_StopProcessing(M1);
          }
          else
          {
            bool LoopClosed;
            int16_t hForcedMecSpeedUnit;

            if (! RUC_Exec(&RevUpControlM1))
            {
              /* The time allowed for the startup sequence has expired */
              MCI_FaultProcessing(&Mci[M1], MC_START_UP, 0);
            }
            else
            {
              /* Compute the virtual speed and positions of the rotor.
                 The function returns true if the virtual speed is in the reliability range */
              LoopClosed = VSS_CalcAvrgMecSpeedUnit(&VirtualSpeedSensorM1, &hForcedMecSpeedUnit);
              /* Check if the transition ramp has completed. */
              bool tempBool;
              tempBool = VSS_TransitionEnded(&VirtualSpeedSensorM1);
              LoopClosed = LoopClosed || tempBool;

              /* If any of the above conditions is true, the loop is considered closed.
                 The state machine transitions to the RUN state */
              if (true ==  LoopClosed)
              {
#if PID_SPEED_INTEGRAL_INIT_DIV == 0
                PID_SetIntegralTerm(&PIDSpeedHandle_M1, 0);
#else
                PID_SetIntegralTerm(&PIDSpeedHandle_M1,
                                    (((int32_t)FOCVars[M1].Iqdref.q * (int16_t)PID_GetKIDivisor(&PIDSpeedHandle_M1))
                                    / PID_SPEED_INTEGRAL_INIT_DIV));
#endif
                /* USER CODE BEGIN MediumFrequencyTask M1 1 */

                /* USER CODE END MediumFrequencyTask M1 1 */
                STC_SetSpeedSensor(pSTC[M1], &STO_PLL_M1._Super); /* Observer has converged */
                FOC_InitAdditionalMethods(M1);
                FOC_CalcCurrRef(M1);
                STC_ForceSpeedReferenceToCurrentSpeed(pSTC[M1]); /* Init the reference speed to current speed */
                MCI_ExecBufferedCommands(&Mci[M1]); /* Exec the speed ramp after changing of the speed sensor */
                Mci[M1].State = RUN;
              }
            }
          }
          break;
        }

3. HALL_CalcAvrgMecSpeedUnit

hall:

__weak void TSK_MediumFrequencyTaskM1(void)
{
  /* USER CODE BEGIN MediumFrequencyTask M1 0 */

  /* USER CODE END MediumFrequencyTask M1 0 */

  int16_t wAux = 0;
  bool IsSpeedReliable = HALL_CalcAvrgMecSpeedUnit(&HALL_M1, &wAux);

encoder:

__weak void TSK_MediumFrequencyTaskM1(void)
{
  /* USER CODE BEGIN MediumFrequencyTask M1 0 */

  /* USER CODE END MediumFrequencyTask M1 0 */

  int16_t wAux = 0;
  (void)ENC_CalcAvrgMecSpeedUnit(&ENCODER_M1, &wAux);

observer:

__weak void TSK_MediumFrequencyTaskM1(void)
{
  /* USER CODE BEGIN MediumFrequencyTask M1 0 */

  /* USER CODE END MediumFrequencyTask M1 0 */

  int16_t wAux = 0;
  bool IsSpeedReliable = STO_PLL_CalcAvrgMecSpeedUnit(&STO_PLL_M1, &wAux);

4。HALL_CalcElAngle

hall:

__weak uint8_t TSK_HighFrequencyTask(void)
{

  uint16_t hFOCreturn;
  uint8_t bMotorNbr = 0;
  /* USER CODE BEGIN HighFrequencyTask 0 */

  /* USER CODE END HighFrequencyTask 0 */

  (void)HALL_CalcElAngle(&HALL_M1);

encoder:

__weak uint8_t TSK_HighFrequencyTask(void)
{

  uint16_t hFOCreturn;
  uint8_t bMotorNbr = 0;
  /* USER CODE BEGIN HighFrequencyTask 0 */

  /* USER CODE END HighFrequencyTask 0 */

  (void)ENC_CalcAngle(&ENCODER_M1);   /* If not sensorless then 2nd parameter is MC_NULL */

observer

__weak uint8_t TSK_HighFrequencyTask(void)
{

  uint16_t hFOCreturn;
  uint8_t bMotorNbr = 0;
  /* USER CODE BEGIN HighFrequencyTask 0 */

  /* USER CODE END HighFrequencyTask 0 */

  Observer_Inputs_t STO_Inputs; /* Only if sensorless main */

  STO_Inputs.Valfa_beta = FOCVars[M1].Valphabeta;  /* Only if sensorless */
  if (SWITCH_OVER == Mci[M1].State)
  {
    if (!REMNG_RampCompleted(pREMNG[M1]))
    {
      FOCVars[M1].Iqdref.q = (int16_t)REMNG_Calc(pREMNG[M1]);
    }
    else
    {
      /* Nothing to do */
    }
  }
  else
  {
    /* Nothing to do */
  }
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值