Go2Py/examples/02-MuJoCo-sim.ipynb

149 lines
2.8 KiB
Plaintext
Raw Normal View History

2024-03-18 11:36:53 +08:00
{
"cells": [
{
"cell_type": "markdown",
"metadata": {},
"source": [
"# Lowlevel Simulation"
]
},
2024-03-18 11:36:53 +08:00
{
"cell_type": "code",
2024-05-05 08:09:01 +08:00
"execution_count": null,
2024-03-18 11:36:53 +08:00
"metadata": {},
"outputs": [],
"source": [
"from Go2Py.sim.mujoco import Go2Sim\n",
"import numpy as np"
]
},
{
"cell_type": "code",
2024-05-05 08:09:01 +08:00
"execution_count": null,
2024-03-18 11:36:53 +08:00
"metadata": {},
"outputs": [],
"source": [
"robot = Go2Sim(mode='lowlevel')\n",
2024-05-05 08:09:01 +08:00
"robot.standUpReset()"
2024-03-18 11:36:53 +08:00
]
},
{
"cell_type": "code",
2024-05-05 08:09:01 +08:00
"execution_count": null,
2024-03-18 11:36:53 +08:00
"metadata": {},
2024-04-06 03:59:21 +08:00
"outputs": [],
2024-03-18 11:36:53 +08:00
"source": [
2024-05-05 08:09:01 +08:00
"robot.getJointStates()"
2024-03-18 11:36:53 +08:00
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": [
2024-05-05 08:09:01 +08:00
"import mujoco\n",
"import time\n",
"robot.standUpReset()\n",
"for i in range(100000):\n",
" state = robot.getJointStates()\n",
" tau = 20*np.eye(12)@(robot.q0 - state['q']).reshape(12,1)\n",
" robot.setCommands(np.zeros(12), np.zeros(12), np.zeros(12), np.zeros(12), tau)\n",
" robot.step()"
2024-03-18 11:36:53 +08:00
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"# Highlevel Simulation"
]
},
{
"cell_type": "code",
2024-05-27 23:47:55 +08:00
"execution_count": null,
"metadata": {},
2024-05-27 23:47:55 +08:00
"outputs": [],
"source": [
"from Go2Py.sim.mujoco import Go2Sim\n",
"import numpy as np"
]
},
{
"cell_type": "code",
2024-05-27 23:47:55 +08:00
"execution_count": null,
"metadata": {},
2024-05-27 23:47:55 +08:00
"outputs": [],
"source": [
"robot = Go2Sim(mode='highlevel')\n",
"robot.standUpReset()"
]
},
{
"cell_type": "code",
2024-05-27 23:47:55 +08:00
"execution_count": null,
"metadata": {},
2024-05-27 23:47:55 +08:00
"outputs": [],
"source": [
"import time\n",
"robot.standUpReset\n",
"for i in range(10000):\n",
" robot.step(0,0,0., step_height=0,kp=[2, 0.5, 0.5], ki=[0.02, 0.01, 0.01])\n",
" time.sleep(robot.dt)"
]
},
{
"cell_type": "code",
2024-05-27 23:47:55 +08:00
"execution_count": null,
"metadata": {},
2024-05-27 23:47:55 +08:00
"outputs": [],
"source": [
"robot.getLaserScan()"
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": [
"import mujoco\n",
"mujoco.mjMAXVAL"
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": [
2024-05-27 23:47:55 +08:00
"import matplotlib.pyplot as plt\n",
"lidar = robot.getLaserScan(max_range=3.)\n",
"idx = np.where(lidar['dist']!=-1)[0]\n",
"plt.plot(lidar['dist'][idx])"
]
2024-03-18 11:36:53 +08:00
}
],
"metadata": {
"kernelspec": {
"display_name": "b1-env",
"language": "python",
"name": "python3"
},
"language_info": {
"codemirror_mode": {
"name": "ipython",
"version": 3
},
"file_extension": ".py",
"mimetype": "text/x-python",
"name": "python",
"nbconvert_exporter": "python",
"pygments_lexer": "ipython3",
"version": "3.10.12"
2024-03-18 11:36:53 +08:00
}
},
"nbformat": 4,
"nbformat_minor": 2
}