论文阅读:四足机器人对抗运动先验学习稳健和敏捷的行走

论文:Learning Robust and Agile Legged Locomotion Using Adversarial Motion Priors

进一步学习:AMP,baseline方法,TO

摘要:

介绍了一种新颖的系统,通过使用对抗性运动先验 (AMP) 使四足机器人在复杂地形上实现稳健和敏捷的行走。主要贡献包括为机器人生成AMP数据集,并提出一种教师-学生训练框架来学习稳健和敏捷的运动技能。该系统在现实世界应用中显示出前景,克服了先前依赖广泛环境感应或手工设计模型的方法的限制。

方法:

图2

  • Privileged learning

由于地形信息不完全可观察,没有外部感应器,盲行过程被建模为部分可观察的马尔可夫决策过程。

因此借助Privileged learning,即特权学习。

特权学习中,教师策略在模拟中训练,利用只有在模拟中才有的特权状态。然后学生策略学习模仿教师的特权状态编码和相应的行为。首先训练一个能够观察到机器人和环境动态属性的教师策略。然后将教师策略提炼到学生策略中,通过监督学习从一系列的观察中推断这些属性。

动作空间:

对于教师策略,状态空间 x teacher t x_{\text{teacher}}^t xteachert包含以下部分:

  1. 本体感知观察 o p t o_p^t opt:包括重力矢量的方向、基座的角速度、关节位置和速度、由当前策略选择的前一个动作 a t − 1 a_{t-1} at1,以及期望的基座速度命令向量。

  2. 特权状态 s p t s_p^t spt:由于基座的线速度计算来自状态估算算法且含噪声,因此将其作为特权状态的一部分,同时还包括地面摩擦系数、地面恢复系数、接触力、外部力及其在机器人上的位置,以及碰撞状态(包括躯干、大腿和小腿部分)。

  3. 地形信息 i e t i_e^t iet:包含从机器人基座周围的网格中采样的地形点的187项测量数据,代表从采样点到机器人基座的垂直距离。

学生策略只能访问本体感知观察 o p t o_p^t opt,而无法访问特权状态 s p t s_p^t spt和地形信息 i e t i_e^t iet。学生策略需要通过监督学习来模仿教师策略,并从历史观察中推断那些它无法直接观察到的动态属性。

行动空间:策略行动 a t a_t at是一个12维向量,被解释为目标关节位置的偏移量,这个偏移量被加到时间不变的名义关节位置上,以指定每个关节的目标电机位置。然后,关节的PD控制器使用这些目标电机位置和固定增益( K p = 20 , K d = 0.5 K_p = 20, K_d = 0.5 Kp=20,Kd=0.5)计算扭矩命令。

  • Reward Terms Design

在这项工作中,奖励函数由任务组成部分 r t g r_t^g rtg、风格组成部分 r t s r_t^s rts和正则化组成部分 r t l r_t^l rtl构成,即 r t = r t g + r t s + r t l r_t = r_t^g + r_t^s + r_t^l rt=rtg+rts+rtl。任务奖励项包括线性和角速度追踪功能。

风格奖励(引入强化学习的监督项):

风格奖励用于评估示范者行为和智能体行为之间的相似性,意味着它们越相似,智能体就能获得更多的风格奖励。由于我们期望我们的机器人在穿越平坦或不平坦的地形时获得自然平滑的小跑步态,我们使用基于AMP的风格奖励函数鼓励我们的机器人产生与参考数据集D中的相同步态风格的行为。

定义了一个由神经网络参数 ϕ 表示的鉴别器 D ϕ D_\phi Dϕ,来预测状态转换 ( s t , s t + 1 ) (s_t, s_{t+1}) (st,st+1)是来自数据集D的真实样本还是由智能体A生成的伪样本。每个状态 s A M P t ∈ R 31 s_{AMP}^t \in \mathbb{R}^{31} sAMPtR31​ 包含关节位置、关节速度、基座线速度、基座角速度和相对于地形的基座高度。

鉴别器的训练目标定义为: arg min ϕ E ( s t , s t + 1 ) ∼ D [ ( D ϕ ( s t , s t + 1 ) − 1 ) 2 ] + E ( s t , s t + 1 ) ∼ A [ ( D ϕ ( s t , s t + 1 ) + 1 ) 2 ] + α g p 2 E ( s t , s t + 1 ) ∼ D [ ∣ ∣ ∇ ϕ D ϕ ( s t , s t + 1 ) ∣ ∣ 2 ] , \underset{\phi}{\text{arg min}} \ \mathbb{E}_{(s_t, s_{t+1}) \sim D} \left[ (D_\phi (s_t, s_{t+1}) - 1)^2 \right] + \mathbb{E}_{(s_t, s_{t+1}) \sim A} \left[ (D_\phi (s_t, s_{t+1}) + 1)^2 \right] + \frac{\alpha_{gp}}{2} \mathbb{E}_{(s_t, s_{t+1}) \sim D} \left[ ||\nabla_\phi D_\phi (s_t, s_{t+1})||^2 \right], ϕarg min E(st,st+1)D[(Dϕ(st,st+1)1)2]+E(st,st+1)A[(Dϕ(st,st+1)+1)2]+2αgpE(st,st+1)D[∣∣ϕDϕ(st,st+1)2],其中前两项是最小二乘GAN公式,鼓励鉴别器区分给定的输入状态转换是来自智能体A还是参考数据集D。公式中的最后一项是梯度惩罚项,用于减少鉴别器在真实数据样本的流形上分配非零梯度的倾向。 α g p \alpha_{gp} αgp是手动指定的系数(我们使用 α g p = 10 \alpha_{gp} = 10 αgp=10)。然后风格奖励定义为: r t s [ ( s t , s t + 1 ) ∼ A ] = max ⁡ [ 0 , 1 − 0.25 ( d score t − 1 ) 2 ] , r_t^s [(s_t, s_{t+1}) \sim A] = \max \left[ 0, 1 - 0.25 (d_{\text{score}}^t - 1)^2 \right], rts[(st,st+1)A]=max[0,10.25(dscoret1)2],其中 d score t = D ϕ ( s t , s t + 1 ) d_{\text{score}}^t = D_\phi(s_t, s_{t+1}) dscoret=Dϕ(st,st+1)且风格奖励缩放到范围 [0, 1]。

所有奖励项:

术语方程权重作用
任务奖励 r t g r_t^g rtg exp ⁡ ( − ∣ v t , d e s , x y − v t , x y ∣ 2 0.15 ) \exp\left(-\frac{|v_{t,des,xy} - v_{t,xy}|_2}{0.15}\right) exp(0.15vt,des,xyvt,xy2)1.0鼓励匹配目标线速度
exp ⁡ ( − ∣ ω t , d e s , z − ω t , z ∣ 2 0.15 ) \exp\left(-\frac{|\omega_{t,des,z} - \omega_{t,z}|_2}{0.15}\right) exp(0.15ωt,des,zωt,z2)0.5鼓励匹配目标角速度
平滑性奖励 r t l r_t^l rtl ∣ τ t ∣ 2 |\tau_t|_2 τt2 1 × 1 0 − 4 1 \times 10^{-4} 1×104最小化扭矩
∣ q ¨ t ∣ 2 |\ddot{q}_t|_2 q¨t2 2.5 × 1 0 − 7 2.5 \times 10^{-7} 2.5×107鼓励维持低关节速度
∣ q t − 1 − q t ∣ 2 |q_{t-1} - q_t|_2 qt1qt20.1鼓励机器人的关节位置变化更平滑
∑ i = 0 5 min ⁡ ( τ i , t − 0.5 , 0 ) \sum_{i=0}^5 \min(\tau_{i,t} - 0.5, 0) i=05min(τi,t0.5,0)1.0惩罚大扭矩,鼓励机器人使用较小的扭矩
安全性奖励 r t l r_t^l rtl − n c o l l i s o n -n_{collison} ncollison0.1惩罚碰撞
风格奖励 r t s r_t^s rts max ⁡ [ 0 , 1 − 0.25 ( d score t − 1 ) 2 ] \max \left[ 0, 1 - 0.25 (d_{\text{score}}^t - 1)^2 \right] max[0,10.25(dscoret1)2]0.5鼓励机器人产生与参考数据集D中的相同步态风格的行为
  • Motion Dataset Generation

那么如何得到监督数据集D?

由于只需要状态转换来构建运动数据集 D,采用了之前工作中的单一 TO(轨迹优化)公式来在平坦地面上生成具有小跑步态的四足动物的运动。机器人首先使用简化的质心动力学模型来降低计算复杂性,然后转换成一个具有摩擦锥约束和运动学约束的非线性规划问题。为了加快优化速度并避免调整程序,使用 TOWR来解决 TO 问题,这不需要成本函数。数据集 D 包括前进、后退、向左横移、向右横移、左转向、右转向和组合运动轨迹,总持续时间为30秒。使用 TO 生成运动数据集的好处是它们可以完全匹配模拟代理和示范者的状态空间,避免使用其他运动重定向技术。

训练:

模拟:在不同类型的地形上使用 IsaacGym 训练了4096个并行智能体。教师策略和学生策略分别在4亿和2亿模拟时间步骤中进行训练。两个阶段的总训练时间为实际时间七小时。每个 episode 最多持续1000步,相当于20秒,如果达到终止标准则提前终止。策略的控制频率在模拟中为50Hz。

所有训练都在单个NVIDIA RTX 3090Ti GPU上进行。

终止:当机器人达到终止标准时,我们终止一个 episode 并开始下一个,这些标准包括机身与地面的碰撞、剧烈身体倾斜,以及被困很长一段时间。

动态随机化:为了提高我们策略的鲁棒性,并促进从模拟到真实世界的转移,我们随机化了躯干和腿部的质量、施加在机器人身体上的负载的质量和位置、地面摩擦和恢复系数、电机强度、关节级PD增益以及每个 episode 中的初始关节位置。这些动态参数中的一些被视为特权状态 s p t s_p^t spt,以帮助教师策略训练。另外,在模拟训练阶段,同样的观察噪声被加入。

  • Training Curriculum

在这项工作中,我们创建了五种类型的程序生成地形,包括粗糙平地、斜坡、波浪、楼梯和离散台阶。

由于早期阶段强化学习的不稳定性,直接在非常复杂的地形上训练机器人是困难的。我们采用并改进了中的自动化地形课程。我们创建了一个高度场地图,包含20×10网格排列的100种地形。每行都有同类型的地形按难度递增排列,而每种地形的长度和宽度为8米。粗糙平地通过增加的噪声构建,从±1厘米增加到±8厘米。斜坡的倾斜度从0度增加到30度。波浪是由贯穿地形长度的三个正弦波构成,这些波的振幅从20厘米增加到50厘米。楼梯宽度固定为30厘米,台阶高度从5厘米增加到23厘米。离散障碍物只有从±5厘米增加到±15厘米的两个高度等级。训练开始时,所有机器人都平等地被分配到所有类型的最低难度地形。只有当机器人适应了当前地形的难度后,才会被移动到更难的地形。当机器人能够以超过85%的平均线速度跟踪奖励离开当前地形时,就获得了这种适应性。相反,如果它们在一个episode 结束时未能至少走完指令线速度所要求的一半距离,则重置到更容易的地形。为了避免技能遗忘,解决最难地形的机器人将被循环返回到当前地形类型的随机选定难度。

我们的机器人试图通过在训练过程中跟踪不同的速度指令来学习一个条件命令的策略(策略变量包括状态和操作员的速度指令)。在episode 开始时,给机器人一个要跟随的期望指令,这是一个随机生成的向量 v t d e s = ( v x , v y , ω z ) ∈ R 3 v_{t_{des}} = (v_x, v_y, \omega_z) \in \mathbb{R}^3 vtdes=(vx,vy,ωz)R3​,代表基座框架中的纵向速度、横向速度和偏航速度。在地形课程阶段,偏航速度指令是根据当前航向方向与目标航向方向之间的误差计算出来的,这使我们的机器人能够有效地离开地形。目标航向方向是从[−180°, 180°]均匀采样的。我们在地形课程阶段分别从小范围[−1米/秒,1米/秒]中采样纵向速度指令和横向速度指令。

  • Teacher Policy Training and Architecture

在第一阶段的训练中,我们使用邻近策略优化(PPO)训练教师策略。教师策略和鉴别器的训练过程是同步的。教师在环境中执行推演,生成状态转换 ( s A M P t , s A M P t + 1 ) (s_{AMP}^t, s_{AMP}^{t+1}) (sAMPt,sAMPt+1)。然后将这个状态转换提供给鉴别器 D ϕ D_\phi Dϕ以获得 d s c o r e t d_{score}^t dscoret,该分数用于根据公式(4)计算小跑步态风格奖励 r t s r_t^s rts,并加到教师获得的其他奖励中。收集推演数据后,我们优化教师策略 π θ t e a c h e r \pi_\theta^{teacher} πθteacher的参数 θ \theta θ以最大化公式(1)的总折扣回报,以及每个训练步骤中优化鉴别器 D ϕ D_\phi Dϕ的参数 ϕ \phi ϕ以最小化公式(3)中呈现的目标。

教师策略 π θ t e a c h e r \pi_\theta^{teacher} πθteacher包含三个多层感知器(MLP)组件:地形编码器 E θ e E_{\theta}^e Eθe,特权编码器 E θ p E_{\theta}^p Eθp和低级网络,如图2所示。 E θ e E_{\theta}^e Eθe E θ p E_{\theta}^p Eθp将地形信息 i e t ∈ R 187 i_e^t \in \mathbb{R}^{187} ietR187和特权状态 s p t ∈ R 30 s_p^t \in \mathbb{R}^{30} sptR30压缩成低维潜在表示 l e t ∈ R 16 l_e^t \in \mathbb{R}^{16} letR16 l p t ∈ R 8 l_p^t \in \mathbb{R}^{8} lptR8。虽然这种压缩丢失了一些信息,但它保留了最需要的信息,这有助于学生重建潜在表示。 l e t l_e^t let l p t l_p^t lpt首先被合并成一个完整的潜在表示 l t e a c h e r t ∈ R 24 l_{teacher}^t \in \mathbb{R}^{24} lteachertR24。然后将 l t e a c h e r t l_{teacher}^t lteachert和本体感知观察 o p t ∈ R 45 o_p^t \in \mathbb{R}^{45} optR45提供给低级网络,并带有一个tanh输出层以输出高斯分布 a t e a c h e r t ∼ N ( μ t , σ ) a_{teacher}^t \sim \mathcal{N}(\mu_t, \sigma) ateachertN(μt,σ)的均值 μ t ∈ R 12 \mu_t \in \mathbb{R}^{12} μtR12,其中 σ ∈ R 12 \sigma \in \mathbb{R}^{12} σR12表示由PPO确定的动作的方差。教师策略还有一个由MLP提供的评价网络,包含三个隐藏层,以提供广义优势估计的目标值 V t V_t Vt。鉴别器 D ϕ D_\phi Dϕ是一个单一的MLP,带有两个隐藏层和一个线性单元输出层。

  • Student Policy Training and Architecture

学生策略的训练目的是在不使用特权状态 s p t s_p^t spt和地形信息 i e t i_e^t iet的情况下复现教师策略的行为。因此,学生的动态被视为一个部分可观测的马尔可夫决策过程,学生需要考虑观察 o p t o_p^t opt的历史来估计不可观测的状态。我们为学生使用一个记忆编码器来编码历史之间的时序关联。

在学生训练期间,我们通过最小化两个损失来利用监督方式,包括一个模仿损失和一个重构损失,如图2所示。模仿损失使学生能够模仿教师的动作 a t e a c h e r t a_{teacher}^t ateachert。重构损失鼓励学生的记忆编码器重现教师的潜在表示 l t e a c h e r t l_{teacher}^t lteachert。我们使用数据集聚合策略(DAgger)通过推演学生策略来生成样本,以增加鲁棒性。与教师训练相同的课程也应用于学生训练,而不训练鉴别器。

学生策略由一个记忆编码器和一个与教师的低级MLP相同结构的网络组成。记忆编码器通常通过将一系列历史观测堆叠到MLP的输入中来实现,或者使用可以捕捉过去信息的架构,如递归神经网络(RNN)或时间卷积神经网络(TCN)。然而,对于MLP和TCN这样的架构,需要留出一部分记忆空间来存储历史观测,这给机载资源使用带来了很大压力。因此,与其存储完整的历史观测,更有效的方式是使用RNN,这可以在隐藏状态中嵌入过去的历史信息。我们使用长短期记忆(LSTM)作为我们的RNN架构。首先,本体感知观测 o p t o_p^t opt与LSTM的过去隐藏状态 h t − 1 h_{t-1} ht1和细胞状态 c t − 1 c_{t-1} ct1被编码到LSTM模块的当前隐藏状态 h t ∈ R 256 h_t \in \mathbb{R}^{256} htR256,然后传递给 E θ m E_{\theta}^m Eθm来输出学生的潜在表示 l t s t u d e n t l_t^{student} ltstudent。我们重用教师低级网络的学习权重来初始化学生的低级网络,以加速训练。为了使我们的控制器学习稳健的盲行,我们训练学生策略使用50个 o p t o_p^t opt的序列(对应1秒的记忆)。

实验:

硬件:控制器部署在 Unitree Go1 Edu 机器人上,该机器人站立高度为28厘米,重13公斤。机器人上使用的传感器包括关节位置编码器和一个惯性测量单元(IMU)。通过使用 MNN 框架优化的训练后的学生策略,以提高推理速度,并在机载计算机Jetson TX2 NX上运行。在部署时,控制频率为50Hz。

  • 奖励项的消融实验
    图3

为了评估不同奖励项对步态运动的影响,我们额外训练了两个消融策略,考虑了两种类型奖励的组合( r t g + r t s r_t^g + r_t^s rtg+rts r t g + r l t r_t^g + r_l^t rtg+rlt)。所有三个策略都有相同的训练时间和随机种子。图3显示了在模拟中在平坦地面上给定0.6米/秒向前移动指令时,前右腿(大腿和小腿)的位置和速度。使用全部奖励项( r t g + r l t + r t s r_t^g + r_l^t + r_t^s rtg+rlt+rts)训练的策略的关节状态(紫色线条)更接近于轨迹优化(TO)生成的关节状态(红色线条),而不是其他两种。只使用两种奖励( r t g + r t s r_t^g + r_t^s rtg+rts r t g + r l t r_t^g + r_l^t rtg+rlt)训练的策略产生了急促的速度和位置(橙色和蓝色线条)。更重要的是,使用全部奖励项( r t g + r l t + r t s r_t^g + r_l^t + r_t^s rtg+rlt+rts)训练的策略表现出自然而平稳的步态风格,如附件视频所示。这表明,使用基于AMP的预定义步态先验确实可以让机器人学习自然步态,而不限制克服复杂地形的能力。

  • 鲁棒运动的评价

和几个baselines进行比较:

  1. RMA:一个类似的教师-学生训练框架,其中学生策略包含一个一维CNN(卷积神经网络)适应模块和从教师策略复制的低级网络。

  2. Concurrent:策略与显式估计身体状态的状态估计网络一起并发训练。考虑到策略的最终收敛性,在训练过程中没有提供地形信息。

  3. 域随机化:策略直接训练,没有任何特权状态或地形信息。

  4. 内置MPC:MPC(模型预测控制)控制器内置于Unitree Go1 Edu中。

在每次测试中,机器人被给予了一个10秒钟的0.4米/秒的前进命令。如果机器人能够用前后腿越过台阶,则测试成功并通过。我们对每个台阶高度进行了10次测试,并计算了成功率。如图5所示,我们的方法在上下台阶方面胜过了所有其他方法,能够成功地越过高达25厘米的所有台阶。教师-学生训练框架(ours,RMA)因其能够隐式估计地形信息而有效穿越大台阶,而没有地形信息访问权限的控制器(Concurrent,域随机化,内置MPC)在台阶高度超过13厘米时经常导致跌落。然而,当台阶高度超过15厘米时,RMA的性能迅速下降。这种性能差异很可能是由于在训练期间对学生策略的低级网络的不同处理。我们的学生策略重用了教师低级网络的学习权重,并继续使用教师的动作对其进行训练,而RMA则冻结了学生的低级网络。随着地形变得更加困难, l e t l_e^t let的重构误差会变大,且从教师那里复制的固定权重的学生低级网络的输出会不稳定。

我们进一步评估了在多样化环境中所呈现控制器的鲁棒性,如图1和附件视频所示。这些环境包括大型路缘、密集植被、中度岩石、松散瓦砾和草地。其中一些地形可以变形和破碎,表面上的材料属性有着显著的变化。然而,该策略基于本体感知观察的历史学习了鲁棒的运动,并展示了从模拟到在训练期间从未经历过的特征地形的 zero-shot泛化。

  • 敏捷运动的评价

快,见视频。

总结:

通过强化学习(RL)训练的单一策略可以使用简洁的奖励函数和并行训练程序获得既稳健又敏捷的运动。从AMP学习的步态风格展示了从平坦地形的运动数据集到现实世界中的具有挑战性地形的zero-shot泛化。

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。如若转载,请注明出处:http://www.hqwc.cn/news/471873.html

如若内容造成侵权/违法违规/事实不符,请联系编程知识网进行投诉反馈email:809451989@qq.com,一经查实,立即删除!

相关文章

Linux--编译器-gcc/g++使用

目录 前言 1.看一段样例 2.程序的翻译过程 1.第一个阶段:预处理 2.第二个阶段:编译 3.第三个阶段:汇编 4.第四个阶段:链接 3.程序的编译为什么是这个样子? 4. 关于编译器 5.链接(动静态链接&#x…

C++数据结构与算法——字符串

C第二阶段——数据结构和算法,之前学过一点点数据结构,当时是基于Python来学习的,现在基于C查漏补缺,尤其是树的部分。这一部分计划一个月,主要利用代码随想录来学习,刷题使用力扣网站,不定时更…

英文单词-计算:Calculate与Compute的区别是什么

英文单词-计算:Calculate与Compute的区别是什么 compute 源自法语;calculate 源自拉丁语。在使用上,calculate 使用得更为广泛 calculate侧重人的分析,而compute侧重机器的运算。 calculator是“计算器”,而computer是“计算机”…

爬虫之牛刀小试(十一):爬取某东关于手机的评论

首先我们进入华为官方旗舰店,点击Mate60,得到: 找到存放评论的接口网址: 然后使用cookie模拟登录,得到字典筛选出我们想要的内容。 爬取1000条评论 同样可以对任意商品进行操作,得到16款手机共计16000…

Java使用opencsv完成对csv批量操作

文章目录 前言一、maven二、造数三、代码部分1.OpenCsvController2.OpenCsvUtil3.StudentInfo4.CodeToValue 三、效果展示1.download2.upload 总结 前言 csv文件是不同于excel文件的另一种文件,常常以,作为分隔符,本篇将通过JavaBean的形式完成对csv文件…

2024.2.15 模拟实现 RabbitMQ —— 消息持久化

目录 引言 约定存储方式 消息序列化 重点理解 针对 MessageFileManager 单元测试 小结 引言 问题: 关于 Message(消息)为啥在硬盘上存储? 回答: 消息操作并不涉及到复杂的增删查改消息数量可能会非常多&#xff…

【机器学习笔记】8 决策树

决策树原理 决策树是从训练数据中学习得出一个树状结构的模型。 决策树属于判别模型。 决策树是一种树状结构,通过做出一系列决策(选择)来对数据进行划分,这类似于针对一系列问题进行选择。决策树的决策过程就是从根节点开始&…

心理辅导|高校心理教育辅导系统|基于Springboot的高校心理教育辅导系统设计与实现(源码+数据库+文档)

高校心理教育辅导系统目录 目录 基于Springboot的高校心理教育辅导系统设计与实现 一、前言 二、系统功能设计 三、系统实现 1、学生功能模块的实现 (1)学生登录界面 (2)留言反馈界面 (3)试卷列表界…

Java实现实现自动化pdf打水印小项目 使用技术pdfbox、Documents4j

文章目录 前言源码获取一、需求说明二、 调研pdf处理工具word处理工具 三、技术栈选择四、功能实现实现效果详细功能介绍详细代码实现项目目录WordUtilsMain类实现部分:第一部分Main类实现部分:第二部分Main类实现部分:第三部分 资料获取 前言…

win7自带截图工具保存失效解决办法

今日发现一台远航技术的win7中自带的截图工具使用时正常,保存图片时没有弹出保存位置的对话窗口,无法正常保存图片。解决方案如下: 1、进入注册表编辑器。开始-搜索程序和文件-输入 regedit 按下回车键,打开注册表; 2、…

DS Wannabe之5-AM Project: DS 30day int prep day18

Q1. What is Levenshtein Algorithm? Levenshtein算法,也称为编辑距离算法,是一种量化两个字符串之间差异的方法。它通过计算将一个字符串转换成另一个字符串所需的最少单字符编辑操作次数来实现。这些编辑操作包括插入、删除和替换字符。Levenshtein距…

【知识图谱--第三讲知识图谱的存储与查询】

知识图谱的存储与查询 基于关系型数据库的知识图谱存储基于原生图数据库的知识图谱存储原生图数据库实现原理浅析 基于关系型数据库的知识图谱存储 基于原生图数据库的知识图谱存储 原生图数据库实现原理浅析