ROS-noetic+UR5上安装robotiq_85_gripper夹爪

1.在ROS官方下载UR的包

ur机械臂官方:https://github.com/ros-industrial/universal_robot

UR官方目前更新的包感觉嵌套太多了,所以这里我下载的是1.2.7版本的包,这个应该不影响后面的操作。可以先下载后再解压,因为git clone好像只能clone最新的版本。

下载后编译会报错,原因是在view_ur5.launch文件中机器人状态发布节点中type属性出错了,改正后就可以编译成功了。

2.下载robotiq_85_gripper包

ros-industrial:https://github.com/ros-industrial/robotiq

3.在UR5的urdf文件中加入夹爪

最好搞懂UR5的源码,下面是我根据源码分解的一个UR5机械臂,可参考源码理解。

ur5结构描述文件在ur_description/urdf/ur5.urdf.xacro中

直接贴出来吧

<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro">

  <xacro:include filename="$(find ur_description)/urdf/ur.transmission.xacro" />
  <xacro:include filename="$(find ur_description)/urdf/ur.gazebo.xacro" />

  <xacro:macro name="cylinder_inertial" params="radius length mass *origin">
    <inertial>
      <mass value="${mass}" />
      <xacro:insert_block name="origin" />
      <inertia ixx="${0.0833333 * mass * (3 * radius * radius + length * length)}" ixy="0.0" ixz="0.0"
        iyy="${0.0833333 * mass * (3 * radius * radius + length * length)}" iyz="0.0"
        izz="${0.5 * mass * radius * radius}" />
    </inertial>
  </xacro:macro>

  <!-- 定义ur5宏 -->
  <xacro:macro name="ur5_robot" params="prefix joint_limited
    shoulder_pan_lower_limit:=${-pi}    shoulder_pan_upper_limit:=${pi}
    shoulder_lift_lower_limit:=${-pi}    shoulder_lift_upper_limit:=${pi}
    elbow_joint_lower_limit:=${-pi}    elbow_joint_upper_limit:=${pi}
    wrist_1_lower_limit:=${-pi}    wrist_1_upper_limit:=${pi}
    wrist_2_lower_limit:=${-pi}    wrist_2_upper_limit:=${pi}
    wrist_3_lower_limit:=${-pi}    wrist_3_upper_limit:=${pi}
    transmission_hw_interface:=hardware_interface/PositionJointInterface
    safety_limits:=false safety_pos_margin:=0.15
    safety_k_position:=20">

    <!-- Inertia parameters 惯性参数-->
    <xacro:property name="base_mass" value="4.0" />  <!-- This mass might be incorrect -->
    <xacro:property name="shoulder_mass" value="3.7000" />
    <xacro:property name="upper_arm_mass" value="8.3930" />
    <xacro:property name="forearm_mass" value="2.2750" />
    <xacro:property name="wrist_1_mass" value="1.2190" />
    <xacro:property name="wrist_2_mass" value="1.2190" />
    <xacro:property name="wrist_3_mass" value="0.1879" />

    <xacro:property name="shoulder_cog" value="0.0 0.00193 -0.02561" />
    <xacro:property name="upper_arm_cog" value="0.0 -0.024201 0.2125" />
    <xacro:property name="forearm_cog" value="0.0 0.0265 0.11993" />
    <xacro:property name="wrist_1_cog" value="0.0 0.110949 0.01634" />
    <xacro:property name="wrist_2_cog" value="0.0 0.0018 0.11099" />
    <xacro:property name="wrist_3_cog" value="0.0 0.001159 0.0" />

    <!-- Kinematic model 动力学模型-->
    <!-- Properties from urcontrol.conf -->
    <!--
      DH for UR5:
      a = [0.00000, -0.42500, -0.39225,  0.00000,  0.00000,  0.0000]
      d = [0.089159,  0.00000,  0.00000,  0.10915,  0.09465,  0.0823]
      alpha = [ 1.570796327, 0, 0, 1.570796327, -1.570796327, 0 ]
      q_home_offset = [0, -1.570796327, 0, -1.570796327, 0, 0]
      joint_direction = [-1, -1, 1, 1, 1, 1]
      mass = [3.7000, 8.3930, 2.2750, 1.2190, 1.2190, 0.1879]
      center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0, 0.0265], [0, -0.0018, 0.01634], [0, 0.0018,0.01634], [0, 0, -0.001159] ]
    -->
    <xacro:property name="d1" value="0.089159" />
    <xacro:property name="a2" value="-0.42500" />
    <xacro:property name="a3" value="-0.39225" />
    <xacro:property name="d4" value="0.10915" />
    <xacro:property name="d5" value="0.09465" />
    <xacro:property name="d6" value="0.0823" />

    <!-- Arbitrary offsets for shoulder/elbow joints 肩关节/肘关节任意偏移量,根据模型测量-->
    <xacro:property name="shoulder_offset" value="0.13585" />  <!-- measured from model -->
    <xacro:property name="elbow_offset" value="-0.1197" /> <!-- measured from model -->

    <!-- link lengths used in model -->
    <xacro:property name="shoulder_height" value="${d1}" />
    <xacro:property name="upper_arm_length" value="${-a2}" />
    <xacro:property name="forearm_length" value="${-a3}" />
    <xacro:property name="wrist_1_length" value="${d4 - elbow_offset - shoulder_offset}" />
    <xacro:property name="wrist_2_length" value="${d5}" />
    <xacro:property name="wrist_3_length" value="${d6}" />
    <!--property name="shoulder_height" value="0.089159" /-->
    <!--property name="shoulder_offset" value="0.13585" /-->  <!-- shoulder_offset - elbow_offset + wrist_1_length = 0.10915 -->
    <!--property name="upper_arm_length" value="0.42500" /-->
    <!--property name="elbow_offset" value="0.1197" /-->       <!-- CAD measured -->
    <!--property name="forearm_length" value="0.39225" /-->
    <!--property name="wrist_1_length" value="0.093" /-->     <!-- CAD measured -->
    <!--property name="wrist_2_length" value="0.09465" /-->   <!-- In CAD this distance is 0.930, but in the spec it is 0.09465 -->
    <!--property name="wrist_3_length" value="0.0823" /-->

    <xacro:property name="shoulder_radius" value="0.060" />   <!-- manually measured -->
    <xacro:property name="upper_arm_radius" value="0.054" />  <!-- manually measured -->
    <xacro:property name="elbow_radius" value="0.060" />      <!-- manually measured -->
    <xacro:property name="forearm_radius" value="0.040" />    <!-- manually measured -->
    <xacro:property name="wrist_radius" value="0.045" />      <!-- manually measured -->

    <!-- prefix前缀没啥作用,可以加可以不加 -->
    <!-- 底座 -->
    <link name="${prefix}base_link" >
      <visual>
        <geometry>
          <mesh filename="package://ur_description/meshes/ur5/visual/base.dae" />
        </geometry>
        <material name="LightGrey">
          <color rgba="0.7 0.7 0.7 1.0"/>
        </material>
      </visual>
      <collision>
        <geometry>
          <mesh filename="package://ur_description/meshes/ur5/collision/base.stl" />
        </geometry>
      </collision>
      <xacro:cylinder_inertial radius="0.06" length="0.05" mass="${base_mass}">
        <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
      </xacro:cylinder_inertial>
    </link>

    <!-- 绕z轴旋转 肩连杆与底座的关节 -->
    <joint name="${prefix}shoulder_pan_joint" type="revolute">
      <parent link="${prefix}base_link" />
      <child link = "${prefix}shoulder_link" />
      <origin xyz="0.0 0.0 ${shoulder_height}" rpy="0.0 0.0 0.0" />
      <axis xyz="0 0 1" />
      <xacro:unless value="${joint_limited}">
        <limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="150.0" velocity="3.15"/>
        <xacro:if value="${safety_limits}">
          <safety_controller soft_lower_limit="${-2.0 * pi + safety_pos_margin}" soft_upper_limit="${2.0 * pi - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
        </xacro:if>
      </xacro:unless>
      <xacro:if value="${joint_limited}">
        <limit lower="${shoulder_pan_lower_limit}" upper="${shoulder_pan_upper_limit}" effort="150.0" velocity="3.15"/>
        <xacro:if value="${safety_limits}">
          <safety_controller soft_lower_limit="${shoulder_pan_lower_limit + safety_pos_margin}" soft_upper_limit="${shoulder_pan_upper_limit - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
        </xacro:if>
      </xacro:if>
      <dynamics damping="0.0" friction="0.0"/>
    </joint>

    <!-- 肩连杆 -->
    <link name="${prefix}shoulder_link">
      <visual>
        <geometry>
          <mesh filename="package://ur_description/meshes/ur5/visual/shoulder.dae" />
        </geometry>
        <material name="LightGrey">
          <color rgba="0.7 0.7 0.7 1.0"/>
        </material>
      </visual>
      <collision>
        <geometry>
          <mesh filename="package://ur_description/meshes/ur5/collision/shoulder.stl" />
        </geometry>
      </collision>
      <xacro:cylinder_inertial radius="0.06" length="0.15" mass="${shoulder_mass}">
        <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
      </xacro:cylinder_inertial>
    </link>

    <!-- 肩连杆与上臂连杆的关节,绕y轴旋转 -->
    <joint name="${prefix}shoulder_lift_joint" type="revolute">
      <parent link="${prefix}shoulder_link" />
      <child link = "${prefix}upper_arm_link" />
      <origin xyz="0.0 ${shoulder_offset} 0.0" rpy="0.0 ${pi / 2.0} 0.0" />
      <axis xyz="0 1 0" />
      <xacro:unless value="${joint_limited}">
        <limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="150.0" velocity="3.15"/>
        <xacro:if value="${safety_limits}">
          <safety_controller soft_lower_limit="${-2.0 * pi + safety_pos_margin}" soft_upper_limit="${2.0 * pi - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
        </xacro:if>
      </xacro:unless>
      <xacro:if value="${joint_limited}">
        <limit lower="${shoulder_lift_lower_limit}" upper="${shoulder_lift_upper_limit}" effort="150.0" velocity="3.15"/>
        <xacro:if value="${safety_limits}">
          <safety_controller soft_lower_limit="${shoulder_lift_lower_limit + safety_pos_margin}" soft_upper_limit="${shoulder_lift_upper_limit - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
        </xacro:if>
      </xacro:if>
      <dynamics damping="0.0" friction="0.0"/>
    </joint>

    <!-- 上臂连杆 -->
    <link name="${prefix}upper_arm_link">
      <visual>
        <geometry>
          <mesh filename="package://ur_description/meshes/ur5/visual/upperarm.dae" />
        </geometry>
        <material name="LightGrey">
          <color rgba="0.7 0.7 0.7 1.0"/>
        </material>
      </visual>
      <collision>
        <geometry>
          <mesh filename="package://ur_description/meshes/ur5/collision/upperarm.stl" />
        </geometry>
      </collision>
      <xacro:cylinder_inertial radius="0.06" length="0.56" mass="${upper_arm_mass}">
        <origin xyz="0.0 0.0 0.28" rpy="0 0 0" />
      </xacro:cylinder_inertial>
    </link>

    <!-- 肘关节,上臂与前臂的关节 -->
    <joint name="${prefix}elbow_joint" type="revolute">
      <parent link="${prefix}upper_arm_link" />
      <child link = "${prefix}forearm_link" />
      <origin xyz="0.0 ${elbow_offset} ${upper_arm_length}" rpy="0.0 0.0 0.0" />
      <axis xyz="0 1 0" />
      <xacro:unless value="${joint_limited}">
        <limit lower="${-pi}" upper="${pi}" effort="150.0" velocity="3.15"/>
        <xacro:if value="${safety_limits}">
          <safety_controller soft_lower_limit="${-2.0 * pi + safety_pos_margin}" soft_upper_limit="${2.0 * pi - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
        </xacro:if>
      </xacro:unless>
      <xacro:if value="${joint_limited}">
        <limit lower="${elbow_joint_lower_limit}" upper="${elbow_joint_upper_limit}" effort="150.0" velocity="3.15"/>
        <xacro:if value="${safety_limits}">
          <safety_controller soft_lower_limit="${elbow_joint_lower_limit + safety_pos_margin}" soft_upper_limit="${elbow_joint_upper_limit - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
        </xacro:if>
      </xacro:if>
      <dynamics damping="0.0" friction="0.0"/>
    </joint>

    <!-- 前臂连杆 -->
    <link name="${prefix}forearm_link">
      <visual>
        <geometry>
          <mesh filename="package://ur_description/meshes/ur5/visual/forearm.dae" />
        </geometry>
        <material name="LightGrey">
          <color rgba="0.7 0.7 0.7 1.0"/>
        </material>
      </visual>
      <collision>
        <geometry>
          <mesh filename="package://ur_description/meshes/ur5/collision/forearm.stl" />
        </geometry>
      </collision>
      <xacro:cylinder_inertial radius="0.06" length="${-a3}" mass="${forearm_mass}">
        <origin xyz="0.0 0.0 ${-a3/2}" rpy="0 0 0" />
      </xacro:cylinder_inertial>
    </link>

    <!-- 腕关节1,前臂和wrist_1_link的关节 -->
    <joint name="${prefix}wrist_1_joint" type="revolute">
      <parent link="${prefix}forearm_link" />
      <child link = "${prefix}wrist_1_link" />
      <origin xyz="0.0 0.0 ${forearm_length}" rpy="0.0 ${pi / 2.0} 0.0" />
      <axis xyz="0 1 0" />
      <xacro:unless value="${joint_limited}">
        <limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="28.0" velocity="3.2"/>
        <xacro:if value="${safety_limits}">
          <safety_controller soft_lower_limit="${-2.0 * pi + safety_pos_margin}" soft_upper_limit="${2.0 * pi - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
        </xacro:if>
      </xacro:unless>
      <xacro:if value="${joint_limited}">
        <limit lower="${wrist_1_lower_limit}" upper="${wrist_1_upper_limit}" effort="28.0" velocity="3.2"/>
        <xacro:if value="${safety_limits}">
          <safety_controller soft_lower_limit="${wrist_1_lower_limit + safety_pos_margin}" soft_upper_limit="${wrist_1_upper_limit - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
        </xacro:if>
      </xacro:if>
      <dynamics damping="0.0" friction="0.0"/>
    </joint>

    <!-- 腕连杆1 -->
    <link name="${prefix}wrist_1_link">
      <visual>
        <geometry>
          <mesh filename="package://ur_description/meshes/ur5/visual/wrist1.dae" />
        </geometry>
        <material name="LightGrey">
          <color rgba="0.7 0.7 0.7 1.0"/>
        </material>
      </visual>
      <collision>
        <geometry>
          <mesh filename="package://ur_description/meshes/ur5/collision/wrist1.stl" />
        </geometry>
      </collision>
      <xacro:cylinder_inertial radius="0.06" length="0.12" mass="${wrist_1_mass}">
        <origin xyz="0.0 ${wrist_1_length} 0.0" rpy="0 0 0" />
      </xacro:cylinder_inertial>
    </link>

    <!-- 腕连杆1与腕连杆2的关节 -->
    <joint name="${prefix}wrist_2_joint" type="revolute">
      <parent link="${prefix}wrist_1_link" />
      <child link = "${prefix}wrist_2_link" />
      <origin xyz="0.0 ${wrist_1_length} 0.0" rpy="0.0 0.0 0.0" />
      <axis xyz="0 0 1" />
      <xacro:unless value="${joint_limited}">
        <limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="28.0" velocity="3.2"/>
        <xacro:if value="${safety_limits}">
          <safety_controller soft_lower_limit="${-2.0 * pi + safety_pos_margin}" soft_upper_limit="${2.0 * pi - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
        </xacro:if>
      </xacro:unless>
      <xacro:if value="${joint_limited}">
        <limit lower="${wrist_2_lower_limit}" upper="${wrist_2_upper_limit}" effort="28.0" velocity="3.2"/>
        <xacro:if value="${safety_limits}">
          <safety_controller soft_lower_limit="${wrist_2_lower_limit + safety_pos_margin}" soft_upper_limit="${wrist_2_upper_limit - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
        </xacro:if>
      </xacro:if>
      <dynamics damping="0.0" friction="0.0"/>
    </joint>

    <!-- 腕连杆2 -->
    <link name="${prefix}wrist_2_link">
      <visual>
        <geometry>
          <mesh filename="package://ur_description/meshes/ur5/visual/wrist2.dae" />
        </geometry>
        <material name="LightGrey">
          <color rgba="0.7 0.7 0.7 1.0"/>
        </material>
      </visual>
      <collision>
        <geometry>
          <mesh filename="package://ur_description/meshes/ur5/collision/wrist2.stl" />
        </geometry>
      </collision>
      <xacro:cylinder_inertial radius="0.06" length="0.12" mass="${wrist_2_mass}">
        <origin xyz="0.0 0.0 ${wrist_2_length}" rpy="0 0 0" />
      </xacro:cylinder_inertial>
    </link>

    <!-- 腕连杆2与腕连杆3的关节 -->
    <joint name="${prefix}wrist_3_joint" type="revolute">
      <parent link="${prefix}wrist_2_link" />
      <child link = "${prefix}wrist_3_link" />
      <origin xyz="0.0 0.0 ${wrist_2_length}" rpy="0.0 0.0 0.0" />
      <axis xyz="0 1 0" />
      <xacro:unless value="${joint_limited}">
        <limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="28.0" velocity="3.2"/>
        <xacro:if value="${safety_limits}">
          <safety_controller soft_lower_limit="${-2.0 * pi + safety_pos_margin}" soft_upper_limit="${2.0 * pi - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
        </xacro:if>
      </xacro:unless>
      <xacro:if value="${joint_limited}">
        <limit lower="${wrist_3_lower_limit}" upper="${wrist_3_upper_limit}" effort="28.0" velocity="3.2"/>
        <xacro:if value="${safety_limits}">
          <safety_controller soft_lower_limit="${wrist_3_lower_limit + safety_pos_margin}" soft_upper_limit="${wrist_3_upper_limit - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
        </xacro:if>
      </xacro:if>
      <dynamics damping="0.0" friction="0.0"/>
    </joint>

    <!-- 腕连杆3 -->
    <link name="${prefix}wrist_3_link">
      <visual>
        <geometry>
          <mesh filename="package://ur_description/meshes/ur5/visual/wrist3.dae" />
        </geometry>
        <material name="LightGrey">
          <color rgba="0.7 0.7 0.7 1.0"/>
        </material>
      </visual>
      <collision>
        <geometry>
          <mesh filename="package://ur_description/meshes/ur5/collision/wrist3.stl" />
        </geometry>
      </collision>
      <xacro:cylinder_inertial radius="0.0375" length="0.0345" mass="${wrist_3_mass}">
        <origin xyz="0.0 ${wrist_3_length - 0.0345/2} 0.0" rpy="${pi/2} 0 0" />
      </xacro:cylinder_inertial>
    </link>

    <!-- 末端与腕连杆3的关节,固定 -->
    <joint name="${prefix}ee_fixed_joint" type="fixed">
      <parent link="${prefix}wrist_3_link" />
      <child link = "${prefix}ee_link" />
      <origin xyz="0.0 ${wrist_3_length} 0.0" rpy="0.0 0.0 ${pi/2.0}" />
    </joint>

    <!-- 末端连杆 -->
    <link name="${prefix}ee_link">
      <collision>
        <geometry>
          <box size="0.01 0.01 0.01"/>
        </geometry>
        <!-- 摩擦系数 ? -->
        <surface>
          <friction>
            <ode>
              <mu>10</mu>
              <mu2>10</mu2>
            </ode>
          </friction>
        </surface>

        <origin rpy="0 0 0" xyz="-0.01 0 0"/>
      </collision>
    </link>

    <xacro:ur_arm_transmission prefix="${prefix}" hw_interface="${transmission_hw_interface}" />
    <xacro:ur_arm_gazebo prefix="${prefix}" />

    <!-- ROS base_link to UR 'Base' Coordinates transform -->
    <link name="${prefix}base"/>
    <joint name="${prefix}base_link-base_fixed_joint" type="fixed">
      <!-- NOTE: this rotation is only needed as long as base_link itself is
                 not corrected wrt the real robot (ie: rotated over 180
                 degrees)
      -->
      <origin xyz="0 0 0" rpy="0 0 ${-pi}"/>
      <parent link="${prefix}base_link"/>
      <child link="${prefix}base"/>
    </joint>

    <!-- Frame coincident with all-zeros TCP on UR controller -->
    <link name="${prefix}tool0"/>
    <joint name="${prefix}wrist_3_link-tool0_fixed_joint" type="fixed">
      <origin xyz="0 ${wrist_3_length} 0" rpy="${pi/-2.0} 0 0"/>
      <parent link="${prefix}wrist_3_link"/>
      <child link="${prefix}tool0"/>
    </joint>

  </xacro:macro>
</robot>

在加入之前先看一下robotiq_85_gripper.urdf.xacro文件,该文件描述了夹爪的结构

 robotiq_85_gripper其实已经封装的很好了,在上面的代码中,定义了一个robotiq_85_gripper宏,后面有三个参数:

prefix:其实就是一个名称前缀,在实例化宏的时候可以加也可以不加,加了后面可能还要修改一些名称,所以这里就不加了。

parent:表示要把夹爪接到哪个关节上,这里我们是接到UR5的末端ee_link上了。

*origin:origin前有一个“*”,表示这是一个块参数,在实现宏时指的是第一个元素

在ur_description/urdf/ur5_robot.urdf文件中包含robotiq_85_gripper,并且实例化该宏。

 <!-- 把robotiq85_gripper包含进来 -->
 <xacro:include filename="$(find robotiq_85_description)/urdf/robotiq_85_gripper.urdf.xacro" />
 <!--实现robotiq_85_gripper宏,并将gripper装在ee_link上-->
 <xacro:robotiq_85_gripper prefix="" parent="ee_link">
    <origin xyz="0 0 0" rpy="0 0 0" />
 </xacro:robotiq_85_gripper>

添加完成后运行view_ur5.launch文件就可以在rviz中见到机械臂上装上夹爪了。

roslaunch ur_description view_ur5.launch

但是在Gazebo仿真世界中夹爪会散架,在网查找资料,robotiq 2f85 gripper有主动关节(finger joint)和被动关节(mimic joint)。标准Gazebo不支持Mimic 关节仿真, 所以需要安装一个插件,这个插件也是找的别人的。https://github.com/Luchuanzhao/gripper_breakdown_solution

 插件装上之后就OK了

 夹爪装完了,下期准备实现一下机械臂抓取。

  • 9
    点赞
  • 36
    收藏
    觉得还不错? 一键收藏
  • 2
    评论

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

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

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值