{ "cells": [ { "cell_type": "code", "execution_count": 1, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ "pygame 2.5.2 (SDL 2.28.2, Python 3.8.18)\n", "Hello from the pygame community. https://www.pygame.org/contribute.html\n" ] } ], "source": [ "from Go2Py.robot.interface.ros2 import GO2Real, ros2_init, ROS2ExecutorManager\n", "import time\n", "ros2_init()\n", "robot = GO2Real(mode='lowlevel')\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": 3, "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) " ] } ], "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.10" } }, "nbformat": 4, "nbformat_minor": 4 }