【PCL-1.14编译|ROS2】基于rosbag2的点云数据录制的PCL数据集制作

前言


1 准备工作

1-1 深度相机插件配置
   <gazebo reference="camera_link">
      <sensor name="camera" type="depth">
        <pose>0 0 0 0 0 0 0</pose>
        <visualize>true</visualize>
        <update_rate>30</update_rate>
        <camera>
            <horizontal_fov>2</horizontal_fov>
            <image>
                <format>R8G8B8</format>
                <width>640</width>
                <height>480</height>
            </image>
            <distortion>
              <k1>0.0</k1>
              <k2>0.0</k2>
              <k3>0.0</k3>
              <p1>0.0</p1>
              <p2>0.0</p2>
              <center>0.5 0.5</center>
            </distortion>

            <clip>
                <near>.001</near>
                <far>10</far>
            </clip>    
        </camera>
        <plugin name="depth_camera" filename="libgazebo_ros_camera.so">
            <frame_name>camera_optional_link</frame_name>
        </plugin>    


      </sensor>
</gazebo>
  • 编译运行仿真环境并打开RVIZ2
  • 我们订阅点云消息/camera/point并对其可视化,发现点云数据可以正常可视化,故我们的仿真插件配置正常。

1-2 ubuntu22.04 PCL1.12版本bug–visualizer segmentation fault in spinOnce function
viewer.spin(); //能显示点云但是还是会报错Segmentation fault
//或者
viewer.spinOnce(100);//直接报错Segmentation fault,无法显示点云
  • 直接出现段错误,因此官方给出的解决方案是使用新版本的pcl库,至少版本在1.13之可以避免这个问题(或者你去修VTK的代码也不是不行~)

1-3 PCL-1.14源码编译
  • 我们直接前往官方仓库 PCL 1.14.1 releases请添加图片描述

  • 下载最新版的源码Source.tar.gz请添加图片描述

  • 下载后解压,然后我们重命名文件夹为pcl-1.14请添加图片描述

  • 紧接着和平常一样我们创建build文件夹

cd pcl-1.14
mkdir build
cd build
cmake -DCMAKE_BUILD_TYPE=Release ..
make -j4
sudo make -j2 install

请添加图片描述
请添加图片描述

1-4 pcl_conversions以及pcl_ros源码编译安装
  • 然后我们还需要配置安装pcl_conversions以及pcl_ros,同样我们来到官方仓库ros-perception请添加图片描述

  • 我们拉取源码,注意切换分支为我们的ROS2版本Humble

git clone -b humble https://github.com/ros-perception/perception_pcl.git
  • 同样的道理我们分别进入对应的文件夹执行
mkdir build
cd build
cmake ..
make -j4
sudo make install

1-5 测试PCL 1.14
  • 我们创建一个新的功能包
ros2 pkg create pcl_processer --dependencies PCL rclcpp rclpy std_msgs sensor_msgs --node-name pcl_recorder --build-type ament_cmake 
  • 测试,我们新建一个cpp文件
#include <iostream>
#include <pcl/point_types.h>
#include <pcl/io/pcd_io.h>
#include <pcl/visualization/pcl_visualizer.h>

int
main (int argc, char` argv)
{
  // 创建一个点云对象
  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);

  // 填充点云数据
  cloud->width = 5;
  cloud->height = 1;
  cloud->is_dense = false;
  cloud->points.resize (cloud->width * cloud->height);

  for (size_t i = 0; i < cloud->points.size (); ++i)
  {
    cloud->points[i].x = 1024 * rand () / (RAND_MAX + 1.0);
    cloud->points[i].y = 1024 * rand () / (RAND_MAX + 1.0);
    cloud->points[i].z = 1024 * rand () / (RAND_MAX + 1.0);
  }

  // 创建PCL可视化对象
  pcl::visualization::PCLVisualizer viewer ("3D Viewer");
  viewer.addPointCloud<pcl::PointXYZ> (cloud, "sample cloud");
  viewer.spin ();

  return 0;
}

  • 然后我们编写CmakeLists.txt
cmake_minimum_required(VERSION 3.8)
project(pcl_processer)

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
  add_compile_options(-Wall -Wextra -Wpedantic)
endif()

# find dependencies
find_package(ament_cmake REQUIRED)
find_package(PCL REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclpy REQUIRED)
find_package(std_msgs REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(pcl_conversions REQUIRED)

find_package(VTK 9.1 REQUIRED)
find_package(pcl_ros REQUIRED)
# 添加 VTK 头文件目录
include_directories(${VTK_INCLUDE_DIRS})



add_executable(pcl_recorder src/pcl_recorder.cpp)


# 链接 VTK 库
target_link_libraries(pcl_recorder ${VTK_LIBRARIES})




target_link_libraries(pcl_recorder ${PCL_LIBRARIES} ${VTK_LIBRARIES})
target_include_directories(pcl_recorder PUBLIC
  /usr/include/vtk-9.1
  $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
  $<INSTALL_INTERFACE:include>)
target_compile_features(pcl_recorder PUBLIC c_std_99 cxx_std_11)  # Require C99 and C++17
ament_target_dependencies(
  pcl_recorder
  "PCL"
  "rclcpp"
  "rclpy"
  "std_msgs"
  "sensor_msgs"
  "pcl_conversions"
  "pcl_ros"
)

install(TARGETS pcl_recorder
  DESTINATION lib/${PROJECT_NAME})

if(BUILD_TESTING)
  find_package(ament_lint_auto REQUIRED)
  # the following line skips the linter which checks for copyrights
  # comment the line when a copyright and license is added to all source files
  set(ament_cmake_copyright_FOUND TRUE)
  # the following line skips cpplint (only works in a git repo)
  # comment the line when this package is in a git repo and when
  # a copyright and license is added to all source files
  set(ament_cmake_cpplint_FOUND TRUE)
  ament_lint_auto_find_test_dependencies()
endif()

ament_package()

  • 编译运行,程序会得到如下窗口,可以看到窗口内新建了5个随机点云数据,且关闭终端不会出现Segmentation fault说明安装成功,版本bug被消除了。请添加图片描述

1-6 编译报错参考(没报错可以跳过本小节)
1-6-1 vtk链接问题
  • fatal error: vtkSmartPointer.h: 没有那个文件或目录 49 | #include <vtkSmartPointer.h>:在CMakeLists中手动链接/usr/include/vtk-9.1(可以通过locate vtkSmartPointer.h去定位头文件的位置)请添加图片描述
    请添加图片描述
1-6-2 链接不到XXX.so文件
  • 出现缺少XXX.so文件例如请添加图片描述
    请添加图片描述

  • 可以尝试手动查找XXX.so文件的位置,例如缺少libjawt.so

 sudo find / -name libjawt.so

请添加图片描述

  • 然后将路径手动链接即可
 export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:/usr/lib/jvm/java-11-openjdk-amd64/lib/server

1 点云数据订阅和PCL数据转换

1-1 程序总览
  • 我们书写一个订阅方节点订阅仿真的点云信息话题/camera/points,老规矩,我们先运行再看代码
#include "rclcpp/rclcpp.hpp"
#include "sensor_msgs/msg/point_cloud2.hpp"
#include <pcl_conversions/pcl_conversions.h>
#include <pcl/point_types.h>
#include <pcl/PCLPointCloud2.h>
#include <pcl/conversions.h>
class PCLRecorder : public rclcpp::Node
{
public:
    PCLRecorder()
        : Node("pointcloud_subscriber")
    {
        subscription_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
            "/camera/points", 10,
            std::bind(&PCLRecorder::pointCloudCallback, this, std::placeholders::_1));
    }

private:
    void pointCloudCallback(const sensor_msgs::msg::PointCloud2::SharedPtr msg)
    {
        pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);

        pcl::fromROSMsg(*msg, *cloud);

        RCLCPP_INFO(this->get_logger(), "Received point cloud with %zu points", cloud->size());
        
        if (cloud->size() > 0)
        {
            RCLCPP_INFO(this->get_logger(), "First point: (%f, %f, %f)",
                        cloud->points[0].x, cloud->points[0].y, cloud->points[0].z);
        }
    }

    rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr subscription_;
};

int main(int argc, char *argv[])
{
    rclcpp::init(argc, argv);

    rclcpp::spin(std::make_shared<PCLRecorder>());

    rclcpp::shutdown();
    return 0;
}

  • 同时我们配置CMakeList.txt
cmake_minimum_required(VERSION 3.8)
project(pcl_processer)

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
  add_compile_options(-Wall -Wextra -Wpedantic)
endif()

# find dependencies
find_package(ament_cmake REQUIRED)
find_package(PCL REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclpy REQUIRED)
find_package(std_msgs REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(pcl_conversions REQUIRED)

find_package(VTK 9.1 REQUIRED)
find_package(pcl_ros REQUIRED)
# 添加 VTK 头文件目录
include_directories(${VTK_INCLUDE_DIRS})



add_executable(pcl_recorder src/pcl_recorder.cpp)


# 链接 VTK 库
target_link_libraries(pcl_recorder ${VTK_LIBRARIES})




target_link_libraries(pcl_recorder ${PCL_LIBRARIES} ${VTK_LIBRARIES})
target_include_directories(pcl_recorder PUBLIC
  /usr/include/vtk-9.1
  $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
  $<INSTALL_INTERFACE:include>)
target_compile_features(pcl_recorder PUBLIC c_std_99 cxx_std_11)  # Require C99 and C++17
ament_target_dependencies(
  pcl_recorder
  "PCL"
  "rclcpp"
  "rclpy"
  "std_msgs"
  "sensor_msgs"
  "pcl_conversions"
  "pcl_ros"
)

install(TARGETS pcl_recorder
  DESTINATION lib/${PROJECT_NAME})

if(BUILD_TESTING)
  find_package(ament_lint_auto REQUIRED)
  # the following line skips the linter which checks for copyrights
  # comment the line when a copyright and license is added to all source files
  set(ament_cmake_copyright_FOUND TRUE)
  # the following line skips cpplint (only works in a git repo)
  # comment the line when this package is in a git repo and when
  # a copyright and license is added to all source files
  set(ament_cmake_cpplint_FOUND TRUE)
  ament_lint_auto_find_test_dependencies()
endif()

ament_package()

  • 运行程序,发现数据被正常订阅转换请添加图片描述
1-2 报错注意-不要使用pcl_ros/point_cloud.hpp
  • 这里需要千万注意的是,不要包含下属头文件!!!
#include <pcl_ros/point_cloud.hpp>
#include <pcl_conversions/pcl_conversions.h>
#include <pcl/point_types.h>
#include <pcl/PCLPointCloud2.h>
#include <pcl/conversions.h>
1-3 代码详解
  • 我们来看看核心的代码实现
 void pointCloudCallback(const sensor_msgs::msg::PointCloud2::SharedPtr msg)
    {
        pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);

        pcl::fromROSMsg(*msg, *cloud);

        RCLCPP_INFO(this->get_logger(), "Received point cloud with %zu points", cloud->size());
        
        if (cloud->size() > 0)
        {
            RCLCPP_INFO(this->get_logger(), "First point: (%f, %f, %f)",
                        cloud->points[0].x, cloud->points[0].y, cloud->points[0].z);
        }
    }
  • pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
    • 这里创建了一个 pcl::PointCloud 类型的点云对象,类型为 pcl::PointXYZ,表示每个点只包含 3D 坐标(x, y, z)。
    • Ptrpcl::PointCloud 类的智能指针类型,负责管理内存。
    • cloud 是一个新的 pcl::PointCloud 对象的指针,用来存储从 ROS 消息转换而来的点云数据。
  • pcl::fromROSMsg(*msg, *cloud);
    • pcl::fromROSMsg 是 PCL 库提供的函数,用于将 ROS 2 消息类型 sensor_msgs::msg::PointCloud2 转换为 PCL 库使用的 pcl::PointCloud 类型。
  • cloud->size() 获取点云中的点数,也就是 cloud 中存储的点的个数。

1-4 添加可视化
  • 我们在代码中添加可视化数据
#include "rclcpp/rclcpp.hpp"
#include "sensor_msgs/msg/point_cloud2.hpp"
#include <pcl_conversions/pcl_conversions.h>
#include <pcl/point_types.h>
#include <pcl/PCLPointCloud2.h>
#include <pcl/conversions.h>
#include <pcl/visualization/pcl_visualizer.h>

class PCLRecorder : public rclcpp::Node
{
public:
    PCLRecorder()
        : Node("pointcloud_subscriber")
    {
        // 订阅点云话题
        subscription_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
            "/camera/points", 10,
            std::bind(&PCLRecorder::pointCloudCallback, this, std::placeholders::_1));

        // 初始化 PCL Viewer
        viewer_ = std::make_shared<pcl::visualization::PCLVisualizer>("PCL Viewer");
        viewer_->getRenderWindow()->GlobalWarningDisplayOff(); 
        viewer_->setBackgroundColor(0.0, 0.0, 0.0); 
        viewer_->addCoordinateSystem(1.0);
        viewer_->initCameraParameters();
    }

private:
    void pointCloudCallback(const sensor_msgs::msg::PointCloud2::SharedPtr msg)
    {
        pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);

        // 将 ROS 消息转换为 PCL 格式
        pcl::fromROSMsg(*msg, *cloud);

        RCLCPP_INFO(this->get_logger(), "Received point cloud with %zu points", cloud->size());

       
        if (cloud->size() > 0)
        {
           
            RCLCPP_INFO(this->get_logger(), "First point: (%f, %f, %f)",
                        cloud->points[0].x, cloud->points[0].y, cloud->points[0].z);


            if (!viewer_->updatePointCloud(cloud, "cloud"))
            {
                viewer_->addPointCloud< pcl::PointXYZ >(cloud, "cloud");

            }
            else
            {
                viewer_->updatePointCloud(cloud, "cloud");
            }
        }

        
        viewer_->spinOnce(100);
        
    }

    rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr subscription_;
    std::shared_ptr<pcl::visualization::PCLVisualizer> viewer_;
};

int main(int argc, char *argv[])
{
    rclcpp::init(argc, argv);

    // 创建并运行 ROS 2 节点
    rclcpp::spin(std::make_shared<PCLRecorder>());

    // 关闭 ROS 2
    rclcpp::shutdown();
    return 0;
}

  • 运行后我们可以在可视化窗口中出现点云数据请添加图片描述

2 点云信息存储PCD格式文件

2-1 点云储存格式介绍
  • 这一小节我们来看看PCL库中常用的存储格式

  • 我们来看看官网的说明pcd_file_format请添加图片描述

  • PCL(Point Cloud Library提供了几种常见的存储点云数据的方式,主要包括 PCD 格式PLY 格式。其中,PCD(Point Cloud Data)格式是最常见和最被广泛使用的文件格式之一。它提供了一种方便、高效的方式来存储和交换点云数据。

2-2 PCD格式组成
  • PCD 文件的基础组成主要有两个部分:文件头部点云数据。我们将详细介绍每个部分的组成和意义。
2-2-1 文件头部(Header)
  • PCD 文件的头部包含文件的元数据,描述了点云数据的结构和格式。头部包括以下几个关键部分:
  • VERSION:指示 PCD 文件的版本号,通常是 0.70.8 等。例如:
VERSION .7
  • FIELDS:指定点云数据的字段顺序。每个字段代表点云中的一个维度或属性,例如 x, y, z, rgb 等。每个字段后面会跟着数据类型和顺序。这表示点云包含 3D 坐标(x, y, z)和颜色信息(rgb)。例如:
FIELDS x y z rgb
  • SIZE:表示每个字段的大小(以字节为单位)。比如 x, y, z 字段可能是 4 字节(浮点数),而 rgb 字段可能是 4 字节(一个颜色值)。例如:
SIZE 4 4 4 4
  • TYPE:字段的数据类型。常见的数据类型包括 F(浮动的,float),I(整型,int)等。例如:
    • 这里表示所有的字段都是浮动类型(F)。
TYPE F F F F
  • COUNT:表示每个字段的元素个数,通常是 1,因为每个点通常只有一个 x, y, z,以及一个 rgb 值。例如:
COUNT 1 1 1 1
  • WIDTH:表示点云数据的宽度,即每行的点数。对于大多数点云,宽度就是点云中总点数。
WIDTH 1000
  • HEIGHT:表示点云数据的高度。如果是一个平面点云,这通常会设置为 1,表示点云是一个“无序”的点集。如果点云有结构,如图像或网格,则 HEIGHT 可以大于 1
HEIGHT 1
  • VIEWPOINT:提供相机的视点信息,表示从哪个角度或位置采集点云数据。通常这部分是冗余的,可以根据需要省略。
VIEWPOINT 0 0 0 1 0 0 0
  • DATA:指定点云数据的存储格式(ASCII 或二进制)。例如:
DATA ascii
2-2-1 点云数据(Data)
  • CD 文件的点云数据部分是文件的主体部分,存储了实际的点云数据。数据根据文件头部的 DATA 行的指示,可以以 ASCII二进制 格式存储。
    • ASCII 格式:每一行代表一个点,每个字段(如 x, y, z, rgb)由空格或其他分隔符分隔。例如:
      • 这表示两个点,分别为 (1.0, 2.0, 3.0)(4.0, 5.0, 6.0),且它们的颜色分别为红色和绿色。
    1.0 2.0 3.0 255 0 0 4.0 5.0 6.0 0 255 0
    
  • 二进制格式:点云数据以二进制格式存储,相比 ASCII 格式更高效,但不容易阅读和编辑。每个字段的值直接以二进制形式写入文件。二进制数据存储格式较为紧凑,适用于处理大量数据时更加高效。

2-3 代码中存储点云为PCD文件
#include <pcl/io/pcd_io.h>
#include <pcl/point_types.h>

pcl::io::savePCDFileASCII ("test_pcd.pcd", cloud);
  • 我们可以看到保存后的一份PCD文件格式 请添加图片描述

2-4 代码中加载PCD文件并进行可视化
  • 同理我们可以书写代码
#include <iostream>
#include <pcl/io/pcd_io.h>
#include <pcl/point_types.h>
 
pcl::io::loadPCDFile<pcl::PointXYZ> ("test_pcd.pcd", *cloud)

2-5 制作数据集的一种思路
  • 值得一提的是PCL中目前每一一个可以连续存储不同帧点云数据的格式,如果希望存储连续视频的点云数据信息,只能分别连续保存多个PCD文件并进行依次读取来伪造出视频流的效果,但是这是在操作上不是很友好的况且处理数据的保存和读取也不很集成化,也不通用。
  • 因此这里我们提出使用ROS2一个非常好用的工具rosbag2来解决这个问题。

3 rosbag2

3-1 介绍
  • rosbag2 是 ROS 2 中的一个工具和库,用于记录和回放 ROS 2 系统中的话题数据。它是 ROS 1 中 rosbag 的继承和改进,具有更好的性能和灵活性,尤其在支持多种序列化格式和高效的数据存储方面。rosbag2 提供了记录、回放、以及检索 ROS 2 消息的功能,能够帮助开发者有效地进行数据收集、调试、分析和测试。
3-2 使用rosbag2进行录制
  • 我们对点云数据进行录制
ros2 bag record /camera/points

请添加图片描述

  • 我们随时可以点击空格进行暂停和继续录制,当录制完毕后点击ctrl+c发送打断信号会自动进行存储。

  • 我们可以在同级目录下找到

  • 请添加图片描述

  • 我们可以在yaml文件中看到对齐的描述

rosbag2_bagfile_information:
  version: 5
  storage_identifier: sqlite3
  duration:
    nanoseconds: 2360019313
  starting_time:
    nanoseconds_since_epoch: 1732430986643576606
  message_count: 22
  topics_with_message_count:
    - topic_metadata:
        name: /camera/points
        type: sensor_msgs/msg/PointCloud2
        serialization_format: cdr
        offered_qos_profiles: "- history: 3\n  depth: 0\n  reliability: 1\n  durability: 2\n  deadline:\n    sec: 9223372036\n    nsec: 854775807\n  lifespan:\n    sec: 9223372036\n    nsec: 854775807\n  liveliness: 1\n  liveliness_lease_duration:\n    sec: 9223372036\n    nsec: 854775807\n  avoid_ros_namespace_conventions: false"
      message_count: 22
  compression_format: ""
  compression_mode: ""
  relative_file_paths:
    - rosbag2_2024_11_24-14_49_46_0.db3
  files:
    - path: rosbag2_2024_11_24-14_49_46_0.db3
      starting_time:
        nanoseconds_since_epoch: 1732430986643576606
      duration:
        nanoseconds: 2360019313
      message_count: 23
  • 根级别信息rosbag2_bagfile_information
    • version: 5:表示ROS 2包文件格式的版本号,本例为版本5。
    • storage_identifier: sqlite3:指定了包文件使用的存储格式,这里是使用SQLite3数据库引擎。
  • 持续时间*duration:
    • nanoseconds: 2360019313表示记录数据的总持续时间,单位是纳秒。换算后,大约是 2.36秒
  • 开始时间 starting_time:
    • nanoseconds_since_epoch: 1732430986643576606:包文件开始记录的时间戳,单位为纳秒,相对于UNIX时间戳(1970年1月1日)。该值可用于同步其他时间相关的事件。
  • *消息数量:
    • message_count: 22:表示包文件中记录的消息总数,这里为22条消息。
  • *主题及消息数量:topics_with_message_count: 这一部分列出了包文件中的所有主题以及每个主题的消息数量:
    • topic_metadata:
      • name: /camera/points:话题名
      • type: sensor_msgs/msg/PointCloud2:消息类型
      • serialization_format: cdr:消息序列化格式,这里采用的是CDR(Common Data Representation)格式,它是ROS 2中常用的数据序列化方式。
      • offered_qos_profiles::描述了主题的QoS(服务质量)配置:
        • history: 3 表示保存历史消息的最大数目为3条。
        • depth: 0 表示没有额外的消息存储深度。
        • reliability: 1 表示可靠性设置为“可靠传输”,即消息传输必须确保不丢失。
        • durability: 2 表示消息持久化,即即使没有订阅者,数据也会保留。
        • 其他设置如deadlinelifespanliveliness等都与数据传输的时效性和订阅者的活动有关。
  • 压缩格式与模式:compression_formatcompression_mode
    • 这两个字段为空,意味着该包文件没有进行压缩。
  • 整体来看,这个包文件存储的是一个持续时间约2.36秒、包含23条点云数据消息的ROS 2数据集。

3-3 回放ros2bag
  • 我们可以通过以下命令去回放
ros2 bag play ./rosbag2_2024_11_24-14_49_46/ 

请添加图片描述

  • 更多详细的配置请添加图片描述

3-4 数据集回放测试
  • 我们使用键盘控制小车移动并使用rosbag2录制一段很长的数据集,并启动回放功能,同时打开我们的程序请添加图片描述请添加图片描述

4 小节

  • 本节我们讲述了如何通过源码编译安装配置PCL 1.14,并借助gazebo仿真深度相机插件完成了pcl点云数据转换和PCD数据格式存储,最后我们利用ROS2-bag录制了一段可重复播放的点云数据作为数据集。
  • 如有错误,欢迎指出!!!
  • 感谢大家的支持!!!
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值