mujoco构建无物理约束的几何体运动

mujoco构建无物理约束的几何体运动。

中心位置放置立方块,一个圆球围绕中心按照圆的轨迹进行运动。

具体模型定义、代码实现具体如下:

bash 复制代码
#-*-coding:utf-8-*-
# date:2025-12-07
# Author: Eric

import mujoco
import mujoco.viewer
import numpy as np
import time

# 1. 定义MuJoCo XML模型(修复range参数+优化关节)
xml = """
<mujoco model="sphere_circle_trajectory">
    <compiler angle="degree"/>
    <option timestep="0.005"/>  <!-- 仿真步长,越小越平滑 -->
    <worldbody>
        <light diffuse="0.5 0.5 0.5" pos="0 0 3" dir="0 0 -1"/>
        <geom name="ground" type="plane" size="2 2 0.1" rgba="0.5 0.5 0.5 1"/>

        <body name="cube" pos="0 0 0.1">
            <joint type="free"/>
            <geom type="box" size="0.1 0.1 0.1" rgba="0.0 0.0 0.5 1"/>
        </body>

        <!-- 球体 -->
        <body name="sphere" pos="0.0 0.0 0.09">  <!-- z=0.09:球体半径,刚好贴地面 -->
            <!-- 关节:仅允许x/y平移,z轴通过微小range+高阻尼固定 -->
            <joint name="sphere_x" type="slide" axis="1 0 0" damping="1"/>
            <joint name="sphere_y" type="slide" axis="0 1 0" damping="1"/>
            <joint name="sphere_z" type="slide" axis="0 0 1" limited="true"
                   range="0.089 0.091" damping="100"/>  <!-- 微小范围+高阻尼固定z轴 -->
            <geom type="sphere" size="0.09" rgba="0.0 0.9 0.0 1"/>
        </body>
    </worldbody>

    <!-- 控制器:为x/y关节添加位置控制 -->
    <actuator>
        <position name="act_x" joint="sphere_x" kp="1000"/>  <!-- kp:位置增益 -->
        <position name="act_y" joint="sphere_y" kp="1000"/>
    </actuator>
</mujoco>
"""
# from_xml_path
# 2. 初始化MuJoCo模型和数据
model = mujoco.MjModel.from_xml_string(xml)

data = mujoco.MjData(model)

# 3. 定义圆形轨迹参数
circle_radius = 1.0       # 圆半径
center_x, center_y = 0, 0 # 圆心坐标
angular_velocity = 0.3    # 角速度(rad/s),控制运动速度

# 4. 仿真循环(带可视化)
with mujoco.viewer.launch_passive(model, data) as viewer:
    # 固定仿真帧率
    viewer._paused = False
    start_time = time.time()

    while viewer.is_running():
        # 计算当前时间和角度
        current_time = time.time() - start_time
        theta = angular_velocity * current_time  # 随时间变化的角度

        # 计算圆形轨迹的目标位置(x,y)
        target_x = center_x + circle_radius * np.cos(theta)
        target_y = center_y + circle_radius * np.sin(theta)

        # 方式:直接修改物体状态(无物理约束,慎用)
        data.joint("sphere_x").qpos = target_x
        data.joint("sphere_y").qpos = target_y

        # 运行一步仿真
        mujoco.mj_step(model, data)

        # 同步可视化
        viewer.sync()

        # 控制仿真帧率(避免过快)
        time.sleep(model.opt.timestep)

代码执行效果如下:

相关推荐
wadesir1 小时前
用Python实现ggplot2风格绘图(零基础入门Seaborn与Matplotlib美化技巧)
开发语言·python·matplotlib
ㄣ知冷煖★2 小时前
基于openEuler操作系统的图神经网络应用开发:以Cora数据集节点分类为例的研究与实践
python
祝余Eleanor2 小时前
Day32 深入理解SHAP图
人工智能·python·机器学习
int WINGsssss2 小时前
【无标题】
pytorch·分布式·python
q_30238195562 小时前
Python实现基于多模态知识图谱的中医智能辅助诊疗系统:迈向智慧中医的新篇章
开发语言·python·知识图谱
我的xiaodoujiao3 小时前
使用 Python 语言 从 0 到 1 搭建完整 Web UI自动化测试学习系列 31--开源电商商城系统项目实战--加入购物车、提交订单测试场景
python·学习·测试工具·pytest
梨落秋霜3 小时前
Python入门篇【输入input】
开发语言·python
Buxxxxxx3 小时前
DAY 34 模块和库的导入
开发语言·python