VMC(虚拟模型控制)算法详解
VMC 算法简介
虚拟模型控制(Virtual Model Control, VMC)是一种用于腿式机器人运动控制的强大算法。它将腿式机器人的复杂动力学简化为一个虚拟的物理模型,通过对虚拟模型的力和扭矩进行控制,间接实现对实际机器人的控制。
VMC 的核心思想
实际腿式机器人 ←→ 虚拟模型(质量弹簧阻尼系统)
↓
控制器
↓
电机指令VMC 将机器人看作是由质量块(虚拟质量)、弹簧和阻尼器组成的虚拟系统。通过对这个虚拟系统施加虚拟力,可以实现对实际机器人的间接控制。
VMC 的优点
- 直观易懂 - 物理模型清晰,易于理解和调试
- 计算效率高 - 不需要复杂的逆动力学计算
- 鲁棒性好 - 对模型误差和扰动有较好的抵抗能力
- 易于实现 - 可以在实时系统上运行
- 灵活性强 - 便于集成多种控制策略
LeBot 中的应用
LeBot 作为轮腿混合机器人,在腿部运动控制中广泛使用 VMC 算法:
- 行走控制
- 爬坡控制
- 不规则地形适应
- 动态平衡
VMC 的数学基础
虚拟模型
虚拟模型是一个二阶质量弹簧系统:
其中:
- 是虚拟质量
- 是虚拟加速度
- 是弹簧力
- 是阻尼力
- 是控制力
腿部雅可比矩阵
腿部的运动学关系由雅可比矩阵描述:
其中:
- 是脚端速度
- 是雅可比矩阵
- 是关节速度
反过来,虚拟力可以通过雅可比矩阵的转置转换为关节力矩:
VMC 控制系统架构
系统框架
期望位置 x_d
↓
┌─────────────────────────────┐
│ 虚拟模型计算 │
│ x(t), v(t), a(t) │
└─────────────────────────────┘
↓
┌─────────────────────────────┐
│ 力计算 │
│ F = k(x_d - x) + b(v_d - v) │
└─────────────────────────────┘
↓
┌─────────────────────────────┐
│ 雅可比变换 │
│ τ = J^T F │
└─────────────────────────────┘
↓
┌─────────────────────────────┐
│ 电机控制 │
│ PWM 或电流指令 │
└─────────────────────────────┘
↓
腿式机器人VMC 的实现步骤
- 获取当前脚端位置 和速度
- 计算虚拟力
- 计算关节力矩
- 转换为电机指令 发送给电机驱动器
Python 实现
基础 VMC 控制器
python
import numpy as np
from typing import Tuple, List
class VMCController:
"""虚拟模型控制器"""
def __init__(self,
spring_constant: float,
damping_constant: float,
virtual_mass: float = 1.0):
"""
初始化 VMC 控制器
参数:
spring_constant: 虚拟弹簧常数 (k)
damping_constant: 虚拟阻尼常数 (b)
virtual_mass: 虚拟质量 (m)
"""
self.k = spring_constant
self.b = damping_constant
self.m = virtual_mass
# 当前状态
self.x = np.array([0.0, 0.0, 0.0]) # 脚端位置 (x, y, z)
self.v = np.array([0.0, 0.0, 0.0]) # 脚端速度
def calculate_virtual_force(self,
target_position: np.ndarray,
target_velocity: np.ndarray = None) -> np.ndarray:
"""
计算虚拟力
公式:F = k(x_d - x) + b(v_d - v)
参数:
target_position: 目标位置
target_velocity: 目标速度 (可选,默认为0)
返回:
虚拟力
"""
if target_velocity is None:
target_velocity = np.zeros(3)
# 位置误差
position_error = target_position - self.x
# 速度误差
velocity_error = target_velocity - self.v
# 计算虚拟力
F = self.k * position_error + self.b * velocity_error
return F
def jacobian_transpose(self,
angles: np.ndarray) -> np.ndarray:
"""
计算雅可比矩阵的转置
这个是简化版本,实际应根据腿的具体结构计算
参数:
angles: 关节角度 [theta1, theta2, theta3]
返回:
J^T 矩阵
"""
theta1, theta2, theta3 = angles
# 为 LeBot 简化的雅可比矩阵
# 实际值需要根据机械结构计算
L1, L2, L3 = 0.1, 0.15, 0.12 # 关节长度
# 计算雅可比矩阵
J = np.array([
[-L1*np.sin(theta1) - L2*np.sin(theta1+theta2) - L3*np.sin(theta1+theta2+theta3),
-L2*np.sin(theta1+theta2) - L3*np.sin(theta1+theta2+theta3),
-L3*np.sin(theta1+theta2+theta3)],
[L1*np.cos(theta1) + L2*np.cos(theta1+theta2) + L3*np.cos(theta1+theta2+theta3),
L2*np.cos(theta1+theta2) + L3*np.cos(theta1+theta2+theta3),
L3*np.cos(theta1+theta2+theta3)],
[0, 0, 0]
])
return J.T
def compute_torques(self,
target_position: np.ndarray,
current_angles: np.ndarray,
target_velocity: np.ndarray = None) -> np.ndarray:
"""
计算电机力矩
参数:
target_position: 目标脚端位置
current_angles: 当前关节角度
target_velocity: 目标速度
返回:
电机力矩
"""
# 计算虚拟力
F = self.calculate_virtual_force(target_position, target_velocity)
# 计算雅可比转置
J_T = self.jacobian_transpose(current_angles)
# 计算力矩:τ = J^T * F
torques = J_T @ F
return torques
def update_state(self,
current_position: np.ndarray,
current_velocity: np.ndarray):
"""
更新当前状态
参数:
current_position: 当前脚端位置
current_velocity: 当前脚端速度
"""
self.x = current_position.copy()
self.v = current_velocity.copy()
class LeggedRobotVMC:
"""腿式机器人 VMC 控制系统"""
def __init__(self, num_legs: int = 4):
"""
初始化腿式机器人 VMC
参数:
num_legs: 腿的数量
"""
self.num_legs = num_legs
# 为每条腿创建 VMC 控制器
self.controllers = [
VMCController(
spring_constant=100.0,
damping_constant=20.0,
virtual_mass=1.0
)
for _ in range(num_legs)
]
# 机器人身体状态
self.body_position = np.array([0.0, 0.0, 0.0])
self.body_velocity = np.array([0.0, 0.0, 0.0])
self.body_orientation = np.array([0.0, 0.0, 0.0]) # 欧拉角
def compute_leg_targets(self,
gait_phase: float,
desired_body_height: float = 0.2) -> List[np.ndarray]:
"""
计算腿的目标位置(基于步态相位)
参数:
gait_phase: 步态相位 (0 ~ 1)
desired_body_height: 期望身体高度
返回:
每条腿的目标位置列表
"""
leg_targets = []
# 四足步态配置(对角线对称)
# 腿 0 和 2:同相位;腿 1 和 3:反相位
leg_phases = [gait_phase, 1.0 - gait_phase, gait_phase, 1.0 - gait_phase]
# 腿的相对位置(相对于身体中心)
leg_offsets = [
np.array([0.1, 0.1, 0.0]), # 前左腿
np.array([0.1, -0.1, 0.0]), # 前右腿
np.array([-0.1, 0.1, 0.0]), # 后左腿
np.array([-0.1, -0.1, 0.0]) # 后右腿
]
for i in range(self.num_legs):
phase = leg_phases[i]
# 摆动相和支撑相
if phase < 0.5:
# 摆动相:从支撑位置摆回初始位置
stance_z = -desired_body_height
swing_z = -desired_body_height + 0.1 # 抬高脚
# 线性插值
t = phase / 0.5
z = stance_z + (swing_z - stance_z) * t
else:
# 支撑相:保持脚在地面
z = -desired_body_height
# 目标位置
target = leg_offsets[i].copy()
target[2] = z
leg_targets.append(target)
return leg_targets
def control_step(self,
gait_phase: float,
current_leg_positions: List[np.ndarray],
current_leg_velocities: List[np.ndarray],
current_joint_angles: List[np.ndarray]) -> List[np.ndarray]:
"""
执行一个控制步骤
参数:
gait_phase: 当前步态相位
current_leg_positions: 当前腿位置
current_leg_velocities: 当前腿速度
current_joint_angles: 当前关节角度
返回:
每条腿的电机力矩
"""
# 计算目标位置
target_positions = self.compute_leg_targets(gait_phase)
# 为每条腿计算力矩
torques = []
for i in range(self.num_legs):
# 更新控制器状态
self.controllers[i].update_state(
current_leg_positions[i],
current_leg_velocities[i]
)
# 计算力矩
leg_torques = self.controllers[i].compute_torques(
target_positions[i],
current_joint_angles[i]
)
torques.append(leg_torques)
return torques
# 使用示例
if __name__ == "__main__":
# 创建 LeBot 的 VMC 控制系统
vmc_system = LeggedRobotVMC(num_legs=4)
# 模拟控制循环
for step in range(100):
# 步态相位 (0 ~ 1)
gait_phase = (step % 50) / 50.0
# 假设当前传感器数据
current_positions = [np.array([0.1, 0.1, -0.2]) for _ in range(4)]
current_velocities = [np.array([0.0, 0.0, 0.0]) for _ in range(4)]
current_angles = [np.array([0.0, 0.5, -0.5]) for _ in range(4)]
# 计算电机力矩
torques = vmc_system.control_step(
gait_phase,
current_positions,
current_velocities,
current_angles
)
print(f"Step {step}, Phase {gait_phase:.2f}")
for i, tau in enumerate(torques):
print(f" Leg {i} torques: {tau}")高级 VMC 特性
添加重力补偿
python
class AdvancedVMCController(VMCController):
"""高级 VMC 控制器,包含重力补偿"""
def __init__(self, *args, **kwargs):
super().__init__(*args, **kwargs)
self.gravity = 9.81
self.leg_mass = 0.5 # 腿的质量
def compute_torques_with_gravity(self,
target_position: np.ndarray,
current_angles: np.ndarray,
target_velocity: np.ndarray = None) -> np.ndarray:
"""
计算包含重力补偿的电机力矩
参数:
target_position: 目标脚端位置
current_angles: 当前关节角度
target_velocity: 目标速度
返回:
电机力矩
"""
# 计算基本的 VMC 力矩
torques = self.compute_torques(target_position, current_angles, target_velocity)
# 计算重力补偿力矩
theta1, theta2, theta3 = current_angles
# 简化的重力补偿(基于正弦函数近似)
L1, L2, L3 = 0.1, 0.15, 0.12
# 每个关节的重力力矩
tau_gravity = np.array([
self.leg_mass * self.gravity * L1 * np.cos(theta1) * 0.5,
self.leg_mass * self.gravity * L2 * np.cos(theta1 + theta2) * 0.5,
self.leg_mass * self.gravity * L3 * np.cos(theta1 + theta2 + theta3) * 0.5
])
# 添加重力补偿
return torques + tau_gravity参数调整指南
弹簧常数 (k)
- 影响:控制位置误差的反应速度
- 过小:响应缓慢,误差大
- 过大:振荡,可能不稳定
推荐范围:50 ~ 200 N/m
阻尼常数 (b)
- 影响:控制速度响应和稳定性
- 过小:振荡,超调大
- 过大:响应慢,可能无法跟踪
推荐范围:10 ~ 50 N·s/m
虚拟质量 (m)
- 影响:系统的惯性特性
- 过小:对干扰敏感
- 过大:响应缓慢
推荐范围:0.5 ~ 2.0 kg
LeBot VMC 调参流程
初始参数设置
- k = 100, b = 20, m = 1.0
测试位置跟踪
python# 测试阶跃响应 target = np.array([0.2, 0.0, -0.2]) for t in range(200): # 运行控制调整弹簧常数
- 如果响应过快或过慢,调整 k
调整阻尼常数
- 如果有振荡,增加 b
- 如果响应太慢,减少 b
验证稳定性
- 多条腿同时工作
- 不规则地形
总结
VMC 是一种强大且易于理解的腿式机器人控制算法:
- 虚拟模型 简化了复杂的动力学
- 易于调参 通过调整 k 和 b 控制性能
- 鲁棒性好 对模型误差有容错能力
- 计算高效 适合实时控制
在 LeBot 中合理应用 VMC,可以实现稳定、高效的多足运动。
推荐资源
- Pratt, J. E., et al. "Virtual Model Control: An Intuitive Approach for Bipedal Locomotion." The International Journal of Robotics Research, 2001.
- Ghigliazza, R. M., et al. "Dynamics and Stability of Legged Locomotion in the Horizontal Plane." Biological Cybernetics, 2005.