Go2Py/examples/contact_detection.ipynb

255 lines
103 KiB
Plaintext
Raw Normal View History

2024-04-03 14:24:17 +08:00
{
"cells": [
{
2024-04-06 03:59:21 +08:00
"cell_type": "markdown",
2024-04-03 14:24:17 +08:00
"metadata": {},
"source": [
2024-04-06 03:59:21 +08:00
"# Simulated"
2024-04-03 14:24:17 +08:00
]
},
{
"cell_type": "code",
2024-04-06 03:59:21 +08:00
"execution_count": 349,
2024-04-03 14:24:17 +08:00
"metadata": {},
"outputs": [],
"source": [
2024-04-06 03:59:21 +08:00
"from Go2Py.sim.mujoco import Go2Sim\n",
"from Go2Py.robot.model import Go2Model\n",
"from Go2Py.estimation.contact import HysteresisContactDetector\n",
"import pinocchio as pin \n",
"import numpy as np\n",
"import time"
2024-04-03 14:24:17 +08:00
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": [
2024-04-06 03:59:21 +08:00
"model = Go2Model()\n",
2024-04-03 14:24:17 +08:00
"robot = Go2Sim()"
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": [
2024-04-06 03:59:21 +08:00
"contactFilter = HysteresisContactDetector(12, 35)"
2024-04-03 14:24:17 +08:00
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": [
2024-04-06 03:59:21 +08:00
"dataset = []\n",
"dataset_measured = []\n",
"dataset_contact_states = []\n",
"for _ in range(5000):\n",
2024-04-03 14:24:17 +08:00
" time.sleep(0.001)\n",
" state = robot.getJointStates()\n",
2024-04-06 03:59:21 +08:00
" quat = robot.getIMU()['quat']\n",
" quat = np.hstack([quat[1:], quat[0]])\n",
" R = pin.Quaternion(quat).matrix()\n",
2024-04-03 14:24:17 +08:00
" T = np.eye(4)\n",
" T[0:3,0:3] = R\n",
" vel = np.zeros(6)\n",
" model.update(state['q'], state['dq'],T,vel)\n",
2024-04-06 03:59:21 +08:00
" F = model.getGroundReactionForce(state['tau_est'])\n",
" contact_forces = np.array([-F[key][-1] for key in F.keys()])\n",
" contactFilter.update(contact_forces)\n",
" contact_state = contactFilter.getContactStates()\n",
" dataset_contact_states.append(contact_state.copy())\n",
" dataset.append(model.getGroundReactionForce(state['tau_est'])['FR_foot'])\n",
" dataset_measured.append(robot.getFootContacts())\n",
"dataset_measured = np.vstack(dataset_measured)\n",
2024-04-03 14:24:17 +08:00
"\n",
2024-04-06 03:59:21 +08:00
"dataset = np.vstack(dataset)\n",
"dataset_contact_states = np.vstack(dataset_contact_states)"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"# Real Robot"
2024-04-03 14:24:17 +08:00
]
},
{
"cell_type": "code",
2024-04-06 03:59:21 +08:00
"execution_count": 297,
2024-04-03 14:24:17 +08:00
"metadata": {},
"outputs": [],
"source": [
2024-04-06 03:59:21 +08:00
"from Go2Py.robot.interface.dds import GO2Real\n",
"from Go2Py.robot.model import Go2Model\n",
"import time\n",
"from Go2Py.sim.mujoco import Go2Sim\n",
"from Go2Py.robot.fsm import FSM\n",
"import numpy as np\n",
"import pinocchio as pin"
2024-04-03 14:24:17 +08:00
]
},
{
"cell_type": "code",
2024-04-06 03:59:21 +08:00
"execution_count": 2,
2024-04-03 14:24:17 +08:00
"metadata": {},
"outputs": [],
"source": [
2024-04-06 03:59:21 +08:00
"robot = GO2Real(mode='lowlevel')\n",
"model = Go2Model()"
2024-04-03 14:24:17 +08:00
]
},
{
"cell_type": "code",
2024-04-06 03:59:21 +08:00
"execution_count": 293,
"metadata": {},
"outputs": [
{
"data": {
"text/plain": [
"{'q': array([ 0.07208335, 0.71541172, -1.52541149, -0.04195726, 0.77687514,\n",
" -1.53210962, 0.10532299, 0.72009933, -1.50478077, -0.04001439,\n",
" 0.66759801, -1.4734081 ]),\n",
" 'dq': array([ 0.02325314, -0.01162657, 0.0161761 , 0.0155021 , 0.0658839 ,\n",
" 0.01011006, 0.01162657, -0.00775105, -0.00404402, 0.01937762,\n",
" 0.0658839 , -0.06066037]),\n",
" 'ddq': array([0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0., 0.]),\n",
" 'tau_est': array([ 2.49856639, 0.66793358, 7.06484079, -2.22644544, 0.02473828,\n",
" 6.44844532, 1.68220317, 0.5442422 , 6.44844532, -2.54804301,\n",
" 1.06374609, 6.25878525]),\n",
" 'temperature': array([30., 28., 27., 28., 28., 27., 28., 28., 27., 30., 28., 27.])}"
]
},
"execution_count": 293,
"metadata": {},
"output_type": "execute_result"
}
],
"source": [
"state = robot.getJointStates()\n",
"state"
]
},
{
"cell_type": "code",
"execution_count": 323,
2024-04-03 14:24:17 +08:00
"metadata": {},
"outputs": [],
"source": [
2024-04-06 03:59:21 +08:00
"contactFilter = HysteresisContactDetector(12, 35)"
2024-04-03 14:24:17 +08:00
]
},
{
"cell_type": "code",
2024-04-06 03:59:21 +08:00
"execution_count": 348,
2024-04-03 14:24:17 +08:00
"metadata": {},
"outputs": [],
2024-04-06 03:59:21 +08:00
"source": [
"dataset = []\n",
"dataset_measured = []\n",
"dataset_contact_states = []\n",
"for _ in range(5000):\n",
" # time.sleep(0.001)\n",
" state = robot.getJointStates()\n",
" quat = robot.getIMU()['quat']\n",
" quat = np.hstack([quat[1:], quat[0]])\n",
" R = pin.Quaternion(quat).matrix()\n",
" T = np.eye(4)\n",
" T[0:3,0:3] = R\n",
" vel = np.zeros(6)\n",
" model.update(state['q'], state['dq'],T,vel)\n",
" F = model.getGroundReactionForce(state['tau_est'])\n",
" contact_forces = np.array([-F[key][-1] for key in F.keys()])\n",
" contactFilter.update(contact_forces)\n",
" contact_state = contactFilter.getContactStates()\n",
" dataset_contact_states.append(contact_state.copy())\n",
" dataset.append(model.getGroundReactionForce(state['tau_est'])['FR_foot'])\n",
" dataset_measured.append(robot.getFootContacts())\n",
"dataset_measured = np.vstack(dataset_measured)\n",
"dataset = np.vstack(dataset)\n",
"dataset_contact_states = np.vstack(dataset_contact_states)"
]
},
{
"cell_type": "code",
"execution_count": 325,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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
"text/plain": [
"<Figure size 640x480 with 1 Axes>"
]
},
"metadata": {},
"output_type": "display_data"
}
],
"source": [
"import matplotlib.pyplot as plt\n",
"plt.plot(-dataset[:,-1])\n",
"plt.plot(dataset_measured[:,0])\n",
"plt.legend(['estimated', 'sensor'])\n",
"plt.grid(True)"
]
},
{
"cell_type": "code",
"execution_count": 327,
"metadata": {},
"outputs": [
{
"data": {
"text/plain": [
"[<matplotlib.lines.Line2D at 0x7fa7098bfa90>]"
]
},
"execution_count": 327,
"metadata": {},
"output_type": "execute_result"
},
{
"data": {
"image/png": "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
"text/plain": [
"<Figure size 640x480 with 1 Axes>"
]
},
"metadata": {},
"output_type": "display_data"
}
],
"source": [
"plt.plot(dataset_contact_states[:,0])"
]
2024-04-03 14:24:17 +08:00
}
],
"metadata": {
"kernelspec": {
"display_name": "Python 3",
"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",
2024-04-06 03:59:21 +08:00
"version": "3.8.18"
2024-04-03 14:24:17 +08:00
}
},
"nbformat": 4,
"nbformat_minor": 2
}