目录

  • 1 概述
  • 2 滤波 Filters
    • 2.1 PassThrough 截取点云
    • 2.2 VoxelGrid 降采样
    • 2.3 StatisticalOutlierRemoval去离群点
    • 2.4 ProjectInliers 投影点云
    • 2.5 ExtractIndices提取点云子集
    • 2.6 ConditionalRemoval or RadiusOutlierRemoval 去离群点
  • 3 特征 Features
    • 3.1 3D features工作原理
      • 3.1.1 理论入门
      • 3.1.2 输入点云
    • 3.2 估计表面法向量 (surface normals)
      • 3.2.1 理论基础
      • 3.2.2 选择合适的尺度
      • 3.2.3 估计法向量
      • 3.2.4 OpenMP加速计算
    • 3.3 使用Integral Images估计法向量
    • 3.4 PFH描述子
    • 3.5 FPFH描述子
      • 3.5.1 理论入门
      • 3.5.2 与PFH的区别
      • 3.5.3 实现
    • 3.6 其他features

该教程介绍了PCL的各个模块的功能,安装位置,及关系。
原文:PCL Walkthrough

1 概述

PCL主要包含14个模块:滤波 (filters),特征 (features),关键点 (keypoints),配准 (registration),kd树 (KdTree),八叉树 (Octree), 分割 (segmentation),采样一致性 (sample consensus), 表面 (surface), 深度图 (range image),输入/输出 (I/O),可视化 (visualization), 公共 (common), 搜索 (search)。

PCL官网
不同模块文档

2 滤波 Filters

交互模块: Sample Consensus, Kdtree, Octree

2.1 PassThrough 截取点云

沿着特定维度滤波,去除给定范围以内(或以外)的数值。:

// 头文件
...
#include <pcl/filters/passthrough.h>
...
// 创建滤波对象 Create the filtering object
pcl::PassThrough<pcl::PointXYZ> pass;
// 设置点云输入
pass.setInputCloud (cloud);
// 滤波范围,z轴, accepted interval: [0,1]
pass.setFilterFieldName ("z");
pass.setFilterLimits (0.0, 1.0);
// 以下若为true,则选取(<0 || >1.0)范围点云
//pass.setFilterLimitsNegative (true);
//滤波
pass.filter (*cloud_filtered);
...

2.2 VoxelGrid 降采样

点云降采样即减少点的数量。先用VoxelGrid类创建输入点云的三维体素网格(3D voxel grid),然后在每个体素 (3D box)中,所有的点用他们的重心(centroid)近似表示。(使用重心比用voxel的中心能更好表示表面)

//头文件
...
#include <pcl/filters/voxel_grid.h>
...
// 创建滤波对象
pcl::VoxelGrid<pcl::PCLPointCloud2> sor;
sor.setInputCloud (cloud);
// 体素大小: 1cm
sor.setLeafSize (0.01f, 0.01f, 0.01f);
sor.filter (*cloud_filtered);

2.3 StatisticalOutlierRemoval去离群点

一个例子是去除测量误差导致的粗差(remove noisy measurements, outlier):先统计分析每个点的邻域,然后去除不满足特定标准的点。(可以假设每个点到邻域点的平均距离服从高斯分布)

//头文件
...
#include <pcl/filters/statistical_outlier_removal.h>
...
// 创建滤波对象
pcl::StatisticalOutlierRemoval<pcl::PointXYZ> sor;
//输入
sor.setInputCloud (cloud);
// 设置分析的邻域点数量
sor.setMeanK (50);
// 设置标准差乘子阈值 (到邻域平均距离多于1倍标准差的点为outlier)
sor.setStddevMulThresh (1.0);
//滤波 (去除outlier)
sor.filter (*cloud_filtered);
...
// 获取outlier点
sor.setNegative (true);
sor.filter (*cloud_filtered);

2.4 ProjectInliers 投影点云

将点云投影到参数模型(平面,球体等)。参数模型由一组系数(Coefficient)指定。

// 头文件
...
#include <pcl/ModelCoefficients.h>
#include <pcl/filters/project_inliers.h>
...
// 定义 ModelCoefficients, 使用平面模型ax+by+cz+d=0, a=b=d=0,c=1,即XY平面
pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients ());
coefficients->values.resize (4);
coefficients->values[0] = coefficients->values[1] = 0;
coefficients->values[2] = 1.0;
coefficients->values[3] = 0;
// 创建ProjectInliers对象
pcl::ProjectInliers<pcl::PointXYZ> proj;
// 模型类型: 平面
proj.setModelType (pcl::SACMODEL_PLANE);
// 输入
proj.setInputCloud (cloud);
// 设置模型系数
proj.setModelCoefficients (coefficients);
// 滤波
proj.filter (*cloud_projected);

2.5 ExtractIndices提取点云子集

根据分割算法输出的点云子集索引,提取点云子集。

// 头文件
...
#include <pcl/filters/extract_indices.h>
...
// 分割点云,获得inliers (pcl::PointIndices)
seg.setInputCloud (cloud_filtered);
seg.segment (*inliers, *coefficients);
...
// 创建滤波对象
pcl::ExtractIndices<pcl::PointXYZ> extract;
...
// 提取inliers对应的点云
extract.setInputCloud (cloud_filtered);
extract.setIndices (inliers);
extract.setNegative (false);
extract.filter (*cloud_p);

2.6 ConditionalRemoval or RadiusOutlierRemoval 去离群点

ConditionalRemoval去除点云中不满足给定条件的点,RadiusOutlierRemoval去除在一定范围内没有邻域点的点。

// 头文件
#include <pcl/filters/radius_outlier_removal.h>
#include <pcl/filters/conditional_removal.h>
...
// 定义RadiusOutlierRemoval对象
pcl::RadiusOutlierRemoval<pcl::PointXYZ> outrem;
// 输入
outrem.setInputCloud(cloud);
// 参数:搜索半径,最少邻域点数量
outrem.setRadiusSearch(0.8);
outrem.setMinNeighborsInRadius (2);
outrem.setKeepOrganized(true);
// 滤波
outrem.filter (*cloud_filtered);
...
// 条件滤波
// 构造条件, z (0, 0.8)
pcl::ConditionAnd<pcl::PointXYZ>::Ptr range_cond (newpcl::ConditionAnd<pcl::PointXYZ> ());
range_cond->addComparison (pcl::FieldComparison<pcl::PointXYZ>::ConstPtr (newpcl::FieldComparison<pcl::PointXYZ> ("z", pcl::ComparisonOps::GT, 0.0)));
range_cond->addComparison (pcl::FieldComparison<pcl::PointXYZ>::ConstPtr (newpcl::FieldComparison<pcl::PointXYZ> ("z", pcl::ComparisonOps::LT, 0.8)));
// 定义ConditionalRemoval对象
pcl::ConditionalRemoval<pcl::PointXYZ> condrem;
// 设置条件
condrem.setCondition (range_cond);
// 输入
condrem.setInputCloud (cloud);
// 有序点云滤波后仍有序
condrem.setKeepOrganized(true);
//滤波
condrem.filter (*cloud_filtered);

3 特征 Features

理论入门可参考How 3D Features work in PCL。
features库包含点云3D特征估计的数据结构和机制。基于点的邻域信息,3D特征描述了某个点/位置的几何模式信息。query point附近的被选空间称为k近邻(k-neighborhood)。以法向量和曲率为例,先使用octree或kd-tree划分点云空间,然后在划分的空间中搜索最近点(可以选k个最近点,或距离r以内的点)。最后,使用特征值分解,计算法向量/曲率。

交互模块:Common, Search, kdTree, Octree, Range Image

3.1 3D features工作原理

包括3D特征估计方法, pcl::Feature类的内部原理

3.1.1 理论入门

参考: Rusu Dissertation

基于单点信息(几何,颜色,强度等)难以对比不同点的属性(high-level info),为了结合更好的属性、度量信息来更有效区别不同的几何表面,可以采用local descriptor/ shape descriptors/ geometric features描述点云,以上统称为point feature representations

通过考虑周围邻域,点云特征可以有效描述表面几何(surface geometry)。因此,相似表面的特征也是相似的。好的特征对刚性变换、不同采样密度、噪声是鲁棒的。

PCL一般采用fast kd-tree queries近似方法计算查询点的最近邻,两种查询方法:

  • k-search: 获取查询点的k个近邻
  • radius- search : 获取以查询点为球心,半径为r的球内的近邻

3.1.2 输入点云

  • setInputCloud(PointCloudConstPtr &) - mandatory指定输入点云,在该点云上提取特征
  • setIndices(IndicesConstPtr &) - optional 指定点云子集,只在这些子集上提取特征。如果不指定,则默认全部点提取特征
  • setSearchSurface(PointCloudConstPtr &) - optional 指定近邻搜索的点集合。如果不指定,默认为输入点云。

当我们有两个点云,P={p1,p2,…,pn }, Q={q1, q2, …, qn}

图1,setIndices() = false, setSearchSurface() = false ,最常用的情况,遍历计算所有P中点的特征。
图2,setIndices() = true, setSearchSurface() = false,只计算p1特征
图3,setIndices() = false, setSearchSurface() = true,Q={q1,q2}是输入点云,P是search surface,所以计算Q所有点的特征,邻域点取自P。
图4,setIndices() = true, setSearchSurface() = true,对比图3,只计算q1特征。

setSearchSurface最常用的情况是处理非常密集的点云。如果不想在所有点上提取特征,可以基于pcl_keypoints提取关键点或降采样得到点云作为输入(setInputCloud()),原始数据为search surface (setSearchSurface())。

3.2 估计表面法向量 (surface normals)

表面法向量是几何表面的重要属性,在计算机图形学的光照/阴影等特效中应用广泛。给定一个几何表面,很容易计算特定点的法向量。但是当只有若干表面的采样点,有两种思路:

  • 间接法:使用surface meshing方法,得到潜在surface mesh,然后估计法向量
  • 直接法:直接从采样点近似计算法法向量 (重点)

3.2.1 理论基础

表面上某点的法向量是通过计算切平面的法向量近似的,因此转变为一个最小二乘平面拟合估计问题。首先,搜索query point的最近邻点,计算这些点对应的协方差矩阵,该矩阵的特征值和特征向量 (或PCA)则反映了表面法向量。对于点pip_ipi​,计算协方差矩阵CCC
如下:
C=1k∑i=1k⋅(pi−pˉ)⋅(pi−pˉ)T,C⋅vj⃗=λj⋅vj⃗,j∈{0,1,2}C = \frac{1}{k}\sum_{i=1}^{k}\cdot(p_i-\bar{p})\cdot(p_i-\bar{p})^{T},C\cdot\vec{v_j} = \lambda_j\cdot\vec{v_j},j\in\{0,1,2\} C=k1​i=1∑k​⋅(pi​−pˉ​)⋅(pi​−pˉ​)T,C⋅vj​​=λj​⋅vj​​,j∈{0,1,2}
kkk是pip_ipi​的最近邻数目,pˉ\bar{p}pˉ​表示最近邻的3D重心,λj\lambda_jλj​是协方差矩阵的第jjj个特征值,vj⃗\vec{v_j}vj​​是第jjj个特征向量。

用Eigen计算协方差矩阵:

 // Placeholder for the 3x3 covariance matrix at each surface patchEigen::Matrix3f covariance_matrix;// 16-bytes aligned placeholder for the XYZ centroid of a surface patchEigen::Vector4f xyz_centroid;// Estimate the XYZ centroidcompute3DCentroid (cloud, xyz_centroid);// Compute the 3x3 covariance matrixcomputeCovarianceMatrix (cloud, xyz_centroid, covariance_matrix);

当视点(viewpoint) vp{v}_pvp​确定后,为了使所有法向量朝向视点,需满足:
ni⃗⋅(vp−pi)>0\vec{n_i}\cdot(v_p-p_i)>0 ni​​⋅(vp​−pi​)>0
对应PCL中函数:


flipNormalTowardsViewpoint (const PointT &point, float vp_x, float vp_y, float vp_z, Eigen::Vector4f &normal);

注意:当有多个视点,需要更复杂的算法。 参考Rusu Dissertation

3.2.2 选择合适的尺度

基于应用需要的细节层次,选择合适的尺度因子,即k或r。对应函数是pcl::Feature::setKSearch和pcl::Feature::setRadiusSearch。

3.2.3 估计法向量

示例代码

//头文件
#include <pcl/point_types.h>
#include <pcl/features/normal_3d.h>{pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);... read, pass in or create a point cloud ...// 定义法向量估计对象// Create the normal estimation class, and pass the input dataset to itpcl::NormalEstimation<pcl::PointXYZ, pcl::Normal> ne;// 输入ne.setInputCloud (cloud);/// 定义并设置kdtree/ Create an empty kdtree representation, and pass it to the normal estimation object.// Its content will be filled inside the object, based on the given input dataset (as no other search surface is given).pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ> ());ne.setSearchMethod (tree);//输出// Output datasetspcl::PointCloud<pcl::Normal>::Ptr cloud_normals (new pcl::PointCloud<pcl::Normal>);//设置搜索半径// Use all neighbors in a sphere of radius 3cmne.setRadiusSearch (0.03);// 计算// Compute the featuresne.compute (*cloud_normals);// cloud_normals->size () should have the same size as the input cloud->size ()*
}
  • 主要步骤:设置输入,搜索方法(kdtree),搜索半径,计算。
  • compute函数实现:1)得到最近邻,2)计算法向量,3)检查(并纠正)法向量朝向(相对视点,默认(0,0,0))
  • 设置视点:setViewPoint()
  • 计算单点法向量 computePointNormal(),曲率计算公式σ=λ0λ0+λ1+λ2\sigma=\frac{\lambda_0}{\lambda_0+\lambda_1+\lambda_2}σ=λ0​+λ1​+λ2​λ0​​

3.2.4 OpenMP加速计算

多核多线程实现:pcl::NormalEstimationOMP。6-8倍加速。

3.3 使用Integral Images估计法向量

使用integral image处理organized点云。

// 头文件
...
#include <pcl/features/ingegral_image_normal.h>
...
// estimate normals
pcl::IntegralImageNormalEstimation<pcl::PointXYZ, pcl::Normal> ne;
ne.setNormalEstimationMethod (ne.AVERAGE_3D_GRADIENT);
ne.setMaxDepthChangeFactor(0.02f);
ne.setNormalSmoothingSize(10.0f);
ne.setInputCloud(cloud);
ne.compute(*normals);

3.4 PFH描述子

鉴于法向量和曲率表达能力有限,提出更复杂的PFH (Point Feature Histogram)描述子,利用数值直方图描述查询点邻域的几何属性。这个高维超空间信息量丰富,对姿态变换、噪声、采样密度较鲁棒。PFH考虑k近邻内所有点及法向量的相互关系,所以结果依赖每个点的法向量估计。计算复杂度O(k2)O(k^2)O(k2)。如图:

为了计算两个点psp_sps​和ptp_tpt​及其法向量nsn_sns​和ntn_tnt​的相对区别,在psp_sps​上构建局部坐标系uvw:


nsn_sns​与ntn_tnt​的区别可以通过α\alphaα, ϕ\phiϕ, θ\thetaθ三个角度表示。另外,d=∣∣pt−ps∣∣2d=||p_t-p_s||_2d=∣∣pt​−ps​∣∣2​是两个点的距离。综上,可使用四元组<α,ϕ,θ,d><\alpha, \phi, \theta, d><α,ϕ,θ,d>描述一对点的关系(将12个数减少为4个)。

估计一对点的PFH四元组:

computePairFeatures (const Eigen::Vector4f &p1, const Eigen::Vector4f &n1,const Eigen::Vector4f &p2, const Eigen::Vector4f &n2,float &f1, float &f2, float &f3, float &f4);

为了得到一个点PFH表示,需要将四元组集合转化为直方图。若每个特征划分为b份,则创建b4b^4b4个取值范围。处理2.5D数据时,特征d不重要,可忽略。默认PFH实现使用5个划分区间, 不使用d,得到pcl::PFHSignature125 类型。

示例代码:

//头文件 pfh.h
#include <pcl/point_types.h>
#include <pcl/features/pfh.h>{pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);pcl::PointCloud<pcl::Normal>::Ptr normals (new pcl::PointCloud<pcl::Normal> ());... read, pass in or create a point cloud with normals ...... (note: you can create a single PointCloud<PointNormal> if you want) ...// Create the PFH estimation class, and pass the input dataset+normals to itpcl::PFHEstimation<pcl::PointXYZ, pcl::Normal, pcl::PFHSignature125> pfh;pfh.setInputCloud (cloud);pfh.setInputNormals (normals);// alternatively, if cloud is of tpe PointNormal, do pfh.setInputNormals (cloud);// Create an empty kdtree representation, and pass it to the PFH estimation object.// Its content will be filled inside the object, based on the given input dataset (as no other search surface is given).pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ> ());//pcl::KdTreeFLANN<pcl::PointXYZ>::Ptr tree (new pcl::KdTreeFLANN<pcl::PointXYZ> ()); -- older call for PCL 1.5-pfh.setSearchMethod (tree);// Output datasetspcl::PointCloud<pcl::PFHSignature125>::Ptr pfhs (new pcl::PointCloud<pcl::PFHSignature125> ());// Use all neighbors in a sphere of radius 5cm// IMPORTANT: the radius used here has to be larger than the radius used to estimate the surface normals!!!pfh.setRadiusSearch (0.05);// Compute the featurespfh.compute (*pfhs);// pfhs->size () should have the same size as the input cloud->size ()*
}

3.5 FPFH描述子

对于包含n个点的点云,PFH理论计算复杂度是O(nk2)O(nk^2)O(nk2),k是近邻个数。FPFH (Fast PFH)理论计算复杂度是O(nk)O(nk)O(nk)。

3.5.1 理论入门

FPFH包含两步:1)计算查询点pqp_qpq​与其邻域点的三元组<α,ϕ,θ><\alpha, \phi,\theta><α,ϕ,θ>,称为SPFH (Simplified PFH) 。2)加权求和pqp_qpq​及其邻域点的SPFH,得到pqp_qpq​的FPFH。

权重wiw_iwi​表示pqp_qpq​与邻近点的距离。FPFH示意图如下

3.5.2 与PFH的区别

  • FPFH没有计算pqp_qpq​邻域内所有点的相互关系,因此损失部分信息
  • PFH更精确,FPFH包含额外点对(2r范围)
  • FPFH复杂度显著降低,可以实时计算
  • FPFH的histogram更简单。每个特征分成d份,最后叠加起来。

3.5.3 实现

默认将特征分成11份,因为特征不相关,叠加得到33维,使用pcl::FPFHSignature33表示。

...
#include <pcl/features/fpfh.h>
...// Create the FPFH estimation class, and pass the input dataset+normals to itpcl::FPFHEstimation<pcl::PointXYZ, pcl::Normal, pcl::FPFHSignature33> fpfh;fpfh.setInputCloud (cloud);fpfh.setInputNormals (normals);// alternatively, if cloud is of tpe PointNormal, do fpfh.setInputNormals (cloud);// Create an empty kdtree representation, and pass it to the FPFH estimation object.// Its content will be filled inside the object, based on the given input dataset (as no other search surface is given).pcl::search::KdTree<PointXYZ>::Ptr tree (new pcl::search::KdTree<PointXYZ>);fpfh.setSearchMethod (tree);// Output datasetspcl::PointCloud<pcl::FPFHSignature33>::Ptr fpfhs (new pcl::PointCloud<pcl::FPFHSignature33> ());// Use all neighbors in a sphere of radius 5cm// IMPORTANT: the radius used here has to be larger than the radius used to estimate the surface normals!!!fpfh.setRadiusSearch (0.05);// Compute the featuresfpfh.compute (*fpfhs);// fpfhs->size () should have the same size as the input cloud->size ()*
}

OpenMP加速:pcl::FPFHEstimationOMP

3.6 其他features

  • VFH (View Point Features) : 适合目标识别和6自由度姿态估计。
  • NARF:在深度图上检测NARF关键点,然后提取NARF描述子。
  • pcl::MomentOfInertiaEstimation : 基于eccentricity(偏心率)和moment of inertia (惯性矩)计算描述子。也可以提取对齐的坐标轴和有向的边界框。
  • RoPs (Rotational Projection Statistics):3D局部表面描述子,目标识别
  • GASD(Globally Aligned Spatial Distribution descriptors): 全局描述子,用于目标识别和姿态估计。

[PCL教程] PCL漫游之Filter、Features相关推荐

  1. [PCL教程]PCL漫游之Registration,Visualization

    目录 9 配准 Registration 9.1 配准基础 9.2 迭代最近点 ICP 9.2 递增地配准点云 9.3 正态分布变换 NDT 9.3.1 基本原理 9.3.2 代码解读 9.4 交互式 ...

  2. PCL教程-点云分割之圆柱体分割

    原文链接:Cylinder model segmentation - Point Cloud Library 0.0 documentation 目录 处理流程 圆柱分割 程序代码 实验结果 打印结果 ...

  3. PCL教程-点云滤波之体素滤波器(下采样)

    原文链接:Downsampling a PointCloud using a VoxelGrid filter 点云文件下载: table_scene_lms400.pcd 目录 原理 程序代码 PC ...

  4. PCL教程指南-估计点云法向量

    PCL教程指南-Estimating Surface Normals in a PointCloud(估计点云法向量) 官方原文档 点云法向指每个点的法向量,它是基于各点所在邻域范围内估计而出,常用方 ...

  5. 【冰爪游戏】MC教程 —— PCL启动器

    [冰爪游戏]MC教程 -- PCL启动器 作者:BZIClaw 0. 介绍 最近有几款爆火的盗版 MC 软件,其中的佼佼者即使PCL 下载地址点击这里:PCL启动器下载 1. 安装 本节目的:安装成功 ...

  6. Java继承Exception自定义异常类教程以及Javaweb中用Filter拦截并处理异常

    Java继承Exception自定义异常类教程以及Javaweb中用Filter拦截并处理异常 参考文章: (1)Java继承Exception自定义异常类教程以及Javaweb中用Filter拦截并 ...

  7. PCL:PCL可视化显示点云

    (1):引用:仅仅是简单的显示点云,可以使用CloudViewer类.这个类非常简单易用.但要注意,它不是线程安全的.如果要用于多线程,还要参考PCLVisualizer. 需要注意的是,PointC ...

  8. PCL Lesson1 :PCL库PCLVisualizer的简单使用

    PCL库PCLVisualizer的简单使用. 包括实例化对象,填充点云,静态显示和动态显示 #include <stdio.h> #include <string> #inc ...

  9. 【点云处理技术之PCL】PCL中的基本数据类型——PointCloud与PointT

    文章目录 0. PointCloud 1. PointXYZ--x,y,z 2. PointXYZI--x,y,z,intensity 3. PointXYZRGBA--x,y,z,r,g,b,a 4 ...

最新文章

  1. constrain to margins
  2. 手脱UPX v0.89.6 - v1.02
  3. ios swift ios8 模糊
  4. 用BP人工神经网络识别手写数字——《Python也可以》之三
  5. spring 项目中集成 Protocol Buffers 示例
  6. windows导出文件名列表
  7. 970页绝版资料!初高中数学与竞赛知识点+方法技巧,由苏步青当顾问,众多一线名师共同编写!...
  8. 开源项目几点心得,Java架构必会几大技术点
  9. 1333:【例2-2】Blah数集
  10. html笔记——网页中视频播放,文字滚动
  11. day4 终止条件continue和break和return的区别
  12. 搭建深度学习环境及跑通Github代码
  13. C语言学习教程二C语言初探
  14. HDU 4699 对顶栈
  15. 检查xml写的格式是否正确的方法
  16. HAL库版STM32双轮自平衡车(一) ———代码思路和PID基础精讲
  17. 致远OA管理员密码的重置
  18. 电脑pdf怎么转换成excel表格呢?
  19. 在win10上如果使用slickedit + mingw编译代码和debug调试
  20. TALIB 中文文档 Overlap Studies Functions 重叠研究指标

热门文章

  1. 2022年苹果二手报价最新
  2. php循环图案正方形,javascript输出指定行数正方形图案效果的实现方法
  3. 欧姆龙plc学习笔记(四)
  4. 媒体查询 iPad 竖屏
  5. Sheldon Numbers 暴力枚举
  6. IDEA--工欲善其事必先利其器
  7. ubuntu1804安装docker
  8. 用友盟社会化组件,分享到微信和新浪微博
  9. 数据类型与字节(字符)
  10. 新玺配资:市场洗盘调整 注意捕捉短线机会