Go2Py/examples/lowlevel_ros2_interface.ipynb

164 lines
3.4 KiB
Plaintext

{
"cells": [
{
"cell_type": "markdown",
"metadata": {},
"source": [
"# Lowlevel Interface Test"
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": [
"from Go2Py.robot.interface.ros2 import GO2Real, ros2_init, ROS2ExecutorManager\n",
"import time\n",
"ros2_init()\n",
"robot = GO2Real(mode='highlevel')\n",
"ros2_exec_manager = ROS2ExecutorManager()\n",
"ros2_exec_manager.add_node(robot)\n",
"ros2_exec_manager.start()"
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": [
"import time\n",
"import numpy as np\n",
"qs = []\n",
"dqs = []\n",
"taus = []\n",
"stamps = []\n",
"for i in range(5000):\n",
" time.sleep(0.01)\n",
" state = robot.getJointStates()\n",
" q = state['q']\n",
" dq = state['dq']\n",
" tau = state['tau_est']\n",
" stamp = time.time()\n",
" qs.append(q)\n",
" dqs.append(dq)\n",
" taus.append(tau)\n",
" stamps.append(stamp)\n",
"\n",
"q=np.array(qs)\n",
"dq=np.array(dqs)\n",
"tau=np.array(taus)\n",
"stamp=np.array(stamps)"
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": [
"import pickle\n",
"with open('go2_rotation.pkl', 'wb') as f:\n",
" pickle.dump(\n",
" {\n",
" 'q':q,\n",
" 'dq':dq, \n",
" 'tau':tau, \n",
" 'stamp':stamp\n",
" }\n",
" ,f\n",
" )"
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": [
"import numpy as np\n",
"import time\n",
"for i in range(10000):\n",
" q = np.zeros(12) \n",
" dq = np.zeros(12)\n",
" kp = np.zeros(12)\n",
" kd = np.zeros(12)\n",
" tau = np.zeros(12)\n",
" tau[0] = -0.8\n",
" robot.setCommands(q, dq, kp, kd, tau)\n",
" time.sleep(0.01) "
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": [
"import matplotlib.pyplot as plt\n",
"plt.plot(taus)"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"# Highlevel Interface Test"
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": [
"from Go2Py.robot.interface.ros2 import GO2Real, ros2_init, ROS2ExecutorManager\n",
"import time\n",
"ros2_init()\n",
"robot = GO2Real(mode='highlevel')\n",
"ros2_exec_manager = ROS2ExecutorManager()\n",
"ros2_exec_manager.add_node(robot)\n",
"ros2_exec_manager.start()"
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": [
"robot.getJointStates()"
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": []
}
],
"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",
"version": "3.8.18"
}
},
"nbformat": 4,
"nbformat_minor": 4
}