MuJoCo 相机图片怎么拿?视角调整获取物体图片及实时显示(附代码)

视频讲解:

MuJoCo 相机图片怎么拿?视角调整获取物体图片及实时显示(附代码)

在Mujoco的仿真中,对于识别抓取场景来说,如何获得添加的body等物体的实时图像很重要,今天就分享下如何添加相机视角及可视化小方块(举例)的实时图片。

代码仓库:GitHub - LitchiCheng/mujoco-learning

复制一个scene.xml为scene_withcamera.xml,在xml中添加camera和小方块如下

  <worldbody>
    <light pos="0 0 1.5" dir="0 0 -1" directional="true"/>
    <geom name="floor" size="0 0 0.05" type="plane" material="groundplane"/>
    <camera name="rgb_camera" pos="0 0 1.5" euler="0 0 0" fovy="60"/>
    <body name="cube" pos="0.75 0 0.05">
      <freejoint/>
      <geom type="box" size="0.05 0.02 0.06" rgba="1 0 0 1" mass="0.01" friction="3.0 2.0 0.003"/>
    </body>
  </worldbody>

需要创建一个离屏渲染器

resolution = (640, 480) 
# 创建OpenGL上下文(离屏渲染)
glfw.init()
glfw.window_hint(glfw.VISIBLE, glfw.FALSE)
window = glfw.create_window(resolution[0], resolution[1], "Offscreen", None, None)
glfw.make_context_current(window)

设置xml文件中添加的相机body id

# 设置相机参数
camera_name = "rgb_camera"
camera_id = mujoco.mj_name2id(model, mujoco.mjtObj.mjOBJ_CAMERA, camera_name)
camera = mujoco.MjvCamera()
# 使用固定相机
# camera.type = mujoco.mjtCamera.mjCAMERA_FIXED  
# 设置相机为跟踪模式
camera.type = mujoco.mjtCamera.mjCAMERA_TRACKING
if camera_id != -1:
    print("camera_id", camera_id)
    camera.fixedcamid = camera_id

完整代码:

import mujoco
import numpy as np
import glfw
import cv2

resolution = (640, 480) 
# 创建OpenGL上下文(离屏渲染)
glfw.init()
glfw.window_hint(glfw.VISIBLE, glfw.FALSE)
window = glfw.create_window(resolution[0], resolution[1], "Offscreen", None, None)
glfw.make_context_current(window)

model = mujoco.MjModel.from_xml_path('./franka_emika_panda/scene_withcamera.xml')
data = mujoco.MjData(model)
scene = mujoco.MjvScene(model, maxgeom=10000)
context = mujoco.MjrContext(model, mujoco.mjtFontScale.mjFONTSCALE_150.value)

# 设置相机参数
camera_name = "rgb_camera"
camera_id = mujoco.mj_name2id(model, mujoco.mjtObj.mjOBJ_CAMERA, camera_name)
camera = mujoco.MjvCamera()
# 使用固定相机
# camera.type = mujoco.mjtCamera.mjCAMERA_FIXED  
# 设置相机为跟踪模式
camera.type = mujoco.mjtCamera.mjCAMERA_TRACKING
if camera_id != -1:
    print("camera_id", camera_id)
    camera.fixedcamid = camera_id

# 创建帧缓冲对象
framebuffer = mujoco.MjrRect(0, 0, resolution[0], resolution[1])
mujoco.mjr_setBuffer(mujoco.mjtFramebuffer.mjFB_OFFSCREEN, context)

while True:
    mujoco.mj_step(model, data)
    tracking_body_id = mujoco.mj_name2id(model, mujoco.mjtObj.mjOBJ_BODY, "cube")
    camera.trackbodyid = tracking_body_id
    camera.distance = 1  # 相机与目标的距离
    camera.azimuth = 0    # 水平方位角(度)
    camera.elevation = -90 # 俯仰角(度)
    viewport = mujoco.MjrRect(0, 0, resolution[0], resolution[1])
    mujoco.mjv_updateScene(model, data, mujoco.MjvOption(), 
                         mujoco.MjvPerturb(), camera, 
                         mujoco.mjtCatBit.mjCAT_ALL, scene)
    mujoco.mjr_render(viewport, scene, context)
    rgb = np.zeros((resolution[1], resolution[0], 3), dtype=np.uint8)
    mujoco.mjr_readPixels(rgb, None, viewport, context)
    # 转换颜色空间 (OpenCV使用BGR格式)
    bgr = cv2.cvtColor(np.flipud(rgb), cv2.COLOR_RGB2BGR)
    cv2.imshow('MuJoCo Camera Output', bgr)
    if cv2.waitKey(1) == 27:
        break

cv2.imwrite('debug_output.png', bgr)
cv2.destroyAllWindows()
glfw.terminate()
del context
del scene

评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值