在机器人视觉和运动控制领域,相机标定是构建精确视觉系统的基石。不同于真实世界中的相机标定,MuJoCo仿真环境中的相机标定往往被开发者忽视——很多人认为虚拟相机"天生完美",不需要标定。但实际开发中我发现,即便是仿真环境,严格的标定流程也能帮助我们发现参数传递错误、坐标系转换等问题。
这次我要分享的,是如何在MuJoCo中实现高精度的虚拟相机标定。这个方法有三大实用价值:
相机内参矩阵K将3D点映射到2D像素坐标,其结构如下:
$$
K=\begin{bmatrix}
f_x & s & c_x \
0 & f_y & c_y \
0 & 0 & 1
\end{bmatrix}
$$
其中:
在MuJoCo中,这些参数可以通过fovy(垂直视场角)和图像分辨率直接计算得到。例如对于640x480图像,fovy=60°时:
python复制f = 0.5 * height / math.tan(fovy * math.pi / 360) # ≈554.26
CAMERA_MATRIX = np.array([
[f, 0, width/2],
[0, f, height/2],
[0, 0, 1]
])
棋盘格标定板提供了已知空间坐标的特征点(角点)。通过观察这些点在图像中的投影变形,可以反推出相机参数。关键点在于:
在MuJoCo中,我通过mocap体控制标定板位姿,用键盘交互实现多角度采集:
python复制if key_states[keyboard.Key.up]:
self.checker_board_z += 0.01 # 深度调整
elif key_states[keyboard.Key.left]:
self.checker_board_x -= 0.01 # 水平移动
self.setMocapPosition("calib_checkerboard", [x, y, z])
首先在XML中定义固定相机:
xml复制<camera name="rgb_camera" pos="0.5 0 0.6" euler="0 0 0" fovy="60"/>
获取图像时需要注意:
python复制# 必须指定fix_elevation使相机正对场景
image = self.getFixedCameraImage(fix_elevation=-90, show=True)
实际开发中发现,直接使用findChessboardCorners在仿真中反而容易失败。我的改进方案:
python复制gray = cv2.cvtColor(image, cv2.COLOR_RGB2GRAY)
gray = cv2.GaussianBlur(gray, (3, 3), 0) # 消除抗锯齿噪声
gray = cv2.Canny(gray, 50, 150) # 边缘强化
ret, corners = cv2.findChessboardCorners(
gray, (6,9), # 根据实际棋盘格调整
cv2.CALIB_CB_ADAPTIVE_THRESH
+ cv2.CALIB_CB_NORMALIZE_IMAGE
+ cv2.CALIB_CB_FAST_CHECK
)
关键提示:仿真图像的完美直线会导致亚像素角点检测不稳定,适当添加高斯模糊反而能提升成功率
建议采用"空间螺旋扫描法"采集数据:
典型采集循环代码结构:
python复制while len(calib_images) < 20: # 建议20组以上
move_checkerboard() # 按策略移动
image = capture_image()
if detect_corners(image):
save_calib_data()
show_feedback()
else:
adjust_position()
标定后会输出关键指标:
code复制平均重投影误差: 0.023541 (越小越好,建议小于0.1)
相机内参矩阵:
[[554.256 0 320]
[0 554.256 240]
[0 0 1]]
畸变系数:
[0 0 0 0 0] # 理想相机应为0
误差来源分析:
通过fovy直接计算的理论值:
code复制[[554.256 0 320]
[0 554.256 240]
[0 0 1]]
标定结果与之完全一致,验证了:
| 现象 | 可能原因 | 解决方案 |
|---|---|---|
| 角点检测失败 | 标定板超出视野 | 调整初始位置 |
| 重投影误差大 | 位姿变化不足 | 增加采集多样性 |
| 畸变系数非零 | 图像预处理不当 | 禁用抗锯齿 |
python复制from threading import Thread
class ImageProcessor(Thread):
def run(self):
while True:
if new_image:
process_image()
python复制for z in np.linspace(0.5, 1.5, 5):
for angle in np.arange(0, 2*np.pi, np.pi/4):
x = 0.5 + 0.2 * np.cos(angle)
y = 0.2 * np.sin(angle)
set_position(x, y, z)
python复制cv2.imshow('Status', np.hstack([original, debug_view]))
cv2.displayOverlay('Status', f"Collected: {len(images)}/20", 1000)
这套方法稍作修改即可用于:
一个进阶应用是构建自动标定系统:
python复制def auto_calibrate():
init_positions = generate_spiral_trajectory()
for pos in init_positions:
move_to(pos)
while not find_optimal_view():
adjust_pose()
capture_and_validate()
return calibrate()
经过多次项目实践,我发现仿真标定最大的价值不在于结果本身,而是通过这个过程建立的参数验证机制。当你在真实机器人上遇到标定问题时,可以快速回仿真环境验证算法是否正确,这种"双向验证"的工作流能极大提升开发效率。