|
| 1 | +{ |
| 2 | + "cells": [ |
| 3 | + { |
| 4 | + "cell_type": "markdown", |
| 5 | + "id": "a756d64a", |
| 6 | + "metadata": {}, |
| 7 | + "source": [ |
| 8 | + "## Start the 3D Visualizer and the droidlet dashboard" |
| 9 | + ] |
| 10 | + }, |
| 11 | + { |
| 12 | + "cell_type": "code", |
| 13 | + "execution_count": null, |
| 14 | + "id": "1825de31", |
| 15 | + "metadata": {}, |
| 16 | + "outputs": [], |
| 17 | + "source": [ |
| 18 | + "from droidlet.dashboard.o3dviz import O3DViz\n", |
| 19 | + "# if False, opens a native window for the 3D visualization. \n", |
| 20 | + "# If True, opens a web-based viewer for the 3D stuff that is available at port http://localhost:8889\n", |
| 21 | + "web_streaming = False \n", |
| 22 | + "o3dviz = O3DViz(web_streaming)\n", |
| 23 | + "o3dviz.start()\n", |
| 24 | + "\n", |
| 25 | + "from droidlet import dashboard\n", |
| 26 | + "dashboard.start()\n", |
| 27 | + "# this has to come after the `dashboard.start` function above\n", |
| 28 | + "from droidlet.event import sio" |
| 29 | + ] |
| 30 | + }, |
| 31 | + { |
| 32 | + "cell_type": "markdown", |
| 33 | + "id": "f909e7f9", |
| 34 | + "metadata": {}, |
| 35 | + "source": [ |
| 36 | + "## Some useful imports" |
| 37 | + ] |
| 38 | + }, |
| 39 | + { |
| 40 | + "cell_type": "code", |
| 41 | + "execution_count": null, |
| 42 | + "id": "b669bc9d", |
| 43 | + "metadata": {}, |
| 44 | + "outputs": [], |
| 45 | + "source": [ |
| 46 | + "import math\n", |
| 47 | + "import time\n", |
| 48 | + "import cv2\n", |
| 49 | + "from matplotlib import pyplot as plt\n", |
| 50 | + "import open3d as o3d\n", |
| 51 | + "import numpy as np" |
| 52 | + ] |
| 53 | + }, |
| 54 | + { |
| 55 | + "cell_type": "markdown", |
| 56 | + "id": "d9dd7932", |
| 57 | + "metadata": {}, |
| 58 | + "source": [ |
| 59 | + "## Import and connect to the HelloRobotMover" |
| 60 | + ] |
| 61 | + }, |
| 62 | + { |
| 63 | + "cell_type": "code", |
| 64 | + "execution_count": null, |
| 65 | + "id": "3f0b7370", |
| 66 | + "metadata": {}, |
| 67 | + "outputs": [], |
| 68 | + "source": [ |
| 69 | + "from droidlet.lowlevel.hello_robot.hello_robot_mover import HelloRobotMover" |
| 70 | + ] |
| 71 | + }, |
| 72 | + { |
| 73 | + "cell_type": "code", |
| 74 | + "execution_count": null, |
| 75 | + "id": "57fa9097", |
| 76 | + "metadata": {}, |
| 77 | + "outputs": [], |
| 78 | + "source": [ |
| 79 | + "mover = HelloRobotMover(ip=\"100.95.90.42\") # ip of the robot\n" |
| 80 | + ] |
| 81 | + }, |
| 82 | + { |
| 83 | + "cell_type": "markdown", |
| 84 | + "id": "959815db", |
| 85 | + "metadata": {}, |
| 86 | + "source": [ |
| 87 | + "## Get the rgb, depth and globally-registered point-clouds" |
| 88 | + ] |
| 89 | + }, |
| 90 | + { |
| 91 | + "cell_type": "code", |
| 92 | + "execution_count": null, |
| 93 | + "id": "c1b3091f", |
| 94 | + "metadata": {}, |
| 95 | + "outputs": [], |
| 96 | + "source": [ |
| 97 | + "rgb_depth = mover.get_rgb_depth()\n", |
| 98 | + "img = rgb_depth.rgb\n", |
| 99 | + "plt.imshow(img)" |
| 100 | + ] |
| 101 | + }, |
| 102 | + { |
| 103 | + "cell_type": "code", |
| 104 | + "execution_count": null, |
| 105 | + "id": "e2728c31", |
| 106 | + "metadata": {}, |
| 107 | + "outputs": [], |
| 108 | + "source": [ |
| 109 | + "plt.imshow(rgb_depth.depth)" |
| 110 | + ] |
| 111 | + }, |
| 112 | + { |
| 113 | + "cell_type": "code", |
| 114 | + "execution_count": null, |
| 115 | + "id": "bef955db", |
| 116 | + "metadata": {}, |
| 117 | + "outputs": [], |
| 118 | + "source": [ |
| 119 | + "def get_open3d_pcd(rgb_depth):\n", |
| 120 | + " points, colors = rgb_depth.ptcloud.reshape(-1, 3), rgb_depth.rgb.reshape(-1, 3)\n", |
| 121 | + " colors = colors / 255.\n", |
| 122 | + " pcd = o3d.geometry.PointCloud()\n", |
| 123 | + " pcd.points = o3d.utility.Vector3dVector(points)\n", |
| 124 | + " pcd.colors = o3d.utility.Vector3dVector(colors)\n", |
| 125 | + " return pcd\n" |
| 126 | + ] |
| 127 | + }, |
| 128 | + { |
| 129 | + "cell_type": "code", |
| 130 | + "execution_count": null, |
| 131 | + "id": "909ba15d", |
| 132 | + "metadata": {}, |
| 133 | + "outputs": [], |
| 134 | + "source": [ |
| 135 | + "point_cloud = get_open3d_pcd(rgb_depth)\n", |
| 136 | + "\n", |
| 137 | + "o3dviz.put('pointcloud', point_cloud)" |
| 138 | + ] |
| 139 | + }, |
| 140 | + { |
| 141 | + "cell_type": "markdown", |
| 142 | + "id": "19d76a11", |
| 143 | + "metadata": {}, |
| 144 | + "source": [ |
| 145 | + "## Get the SLAM obstacle map and base state in droidlet canonical co-ordinates" |
| 146 | + ] |
| 147 | + }, |
| 148 | + { |
| 149 | + "cell_type": "code", |
| 150 | + "execution_count": null, |
| 151 | + "id": "5f05a6d2", |
| 152 | + "metadata": {}, |
| 153 | + "outputs": [], |
| 154 | + "source": [ |
| 155 | + "obstacle_map = mover.get_obstacles_in_canonical_coords()\n", |
| 156 | + "base_state = mover.get_base_pos_in_canonical_coords()" |
| 157 | + ] |
| 158 | + }, |
| 159 | + { |
| 160 | + "cell_type": "code", |
| 161 | + "execution_count": null, |
| 162 | + "id": "de608551", |
| 163 | + "metadata": { |
| 164 | + "scrolled": true |
| 165 | + }, |
| 166 | + "outputs": [], |
| 167 | + "source": [ |
| 168 | + "# Plot them\n", |
| 169 | + "x, y = [m[0] for m in obstacle_map], [m[1] for m in obstacle_map]\n", |
| 170 | + "\n", |
| 171 | + "\n", |
| 172 | + "plt.plot(y, x, 'o', markersize=1)\n", |
| 173 | + "plt.plot(base_state[0], base_state[1], 'ro', markersize=12)\n", |
| 174 | + "\n", |
| 175 | + "xorigin, yorigin = 0., 0.\n", |
| 176 | + "newx = (base_state[0] - xorigin) * math.cos(base_state[2] * math.pi / 180)\n", |
| 177 | + "newy = (base_state[1] - yorigin) * math.sin(base_state[2] * math.pi / 180)\n", |
| 178 | + "plt.plot([base_state[0], newx], [base_state[1], newy], 'b')" |
| 179 | + ] |
| 180 | + }, |
| 181 | + { |
| 182 | + "cell_type": "code", |
| 183 | + "execution_count": null, |
| 184 | + "id": "ce461514", |
| 185 | + "metadata": {}, |
| 186 | + "outputs": [], |
| 187 | + "source": [ |
| 188 | + "# you can also plot it into the dashboard\n", |
| 189 | + "x, y, yaw = base_state\n", |
| 190 | + "sio.emit(\"map\",\n", |
| 191 | + " {\"x\": x, \"y\": y, \"yaw\": yaw, \"map\": obstacle_map},\n", |
| 192 | + ")" |
| 193 | + ] |
| 194 | + }, |
| 195 | + { |
| 196 | + "cell_type": "code", |
| 197 | + "execution_count": null, |
| 198 | + "id": "16aea403", |
| 199 | + "metadata": {}, |
| 200 | + "outputs": [], |
| 201 | + "source": [] |
| 202 | + }, |
| 203 | + { |
| 204 | + "cell_type": "markdown", |
| 205 | + "id": "7178391b", |
| 206 | + "metadata": {}, |
| 207 | + "source": [ |
| 208 | + "## Move the robot using it's navigation system" |
| 209 | + ] |
| 210 | + }, |
| 211 | + { |
| 212 | + "cell_type": "code", |
| 213 | + "execution_count": null, |
| 214 | + "id": "b195a213", |
| 215 | + "metadata": {}, |
| 216 | + "outputs": [], |
| 217 | + "source": [ |
| 218 | + "# Move forward by 1 metre (x, y, yaw)\n", |
| 219 | + "mover.move_relative([1.0, 0.0, 0.0], blocking=False)\n", |
| 220 | + "\n", |
| 221 | + "# turn the robot\n", |
| 222 | + "mover.turn(-math.radians(20))" |
| 223 | + ] |
| 224 | + }, |
| 225 | + { |
| 226 | + "cell_type": "markdown", |
| 227 | + "id": "f35ac20b", |
| 228 | + "metadata": {}, |
| 229 | + "source": [ |
| 230 | + "## Move the robot directly using it's base API" |
| 231 | + ] |
| 232 | + }, |
| 233 | + { |
| 234 | + "cell_type": "code", |
| 235 | + "execution_count": null, |
| 236 | + "id": "a8f40f74", |
| 237 | + "metadata": {}, |
| 238 | + "outputs": [], |
| 239 | + "source": [ |
| 240 | + "mover.bot.go_to_relative([1.0, 0.0, 0.0])" |
| 241 | + ] |
| 242 | + }, |
| 243 | + { |
| 244 | + "cell_type": "markdown", |
| 245 | + "id": "473ed00f", |
| 246 | + "metadata": {}, |
| 247 | + "source": [ |
| 248 | + "## Move it's camera" |
| 249 | + ] |
| 250 | + }, |
| 251 | + { |
| 252 | + "cell_type": "code", |
| 253 | + "execution_count": null, |
| 254 | + "id": "8968ab9c", |
| 255 | + "metadata": {}, |
| 256 | + "outputs": [], |
| 257 | + "source": [ |
| 258 | + "# Set the camera's tilt and pan\n", |
| 259 | + "mover.bot.set_tilt(math.radians(-60) )\n", |
| 260 | + "mover.bot.set_pan(math.radians(-30) )" |
| 261 | + ] |
| 262 | + }, |
| 263 | + { |
| 264 | + "cell_type": "markdown", |
| 265 | + "id": "0564b106", |
| 266 | + "metadata": {}, |
| 267 | + "source": [ |
| 268 | + "## Stop the robot's actions immediately" |
| 269 | + ] |
| 270 | + }, |
| 271 | + { |
| 272 | + "cell_type": "code", |
| 273 | + "execution_count": null, |
| 274 | + "id": "fab0cf71", |
| 275 | + "metadata": {}, |
| 276 | + "outputs": [], |
| 277 | + "source": [ |
| 278 | + "mover.stop()" |
| 279 | + ] |
| 280 | + }, |
| 281 | + { |
| 282 | + "cell_type": "markdown", |
| 283 | + "id": "99cfcd34", |
| 284 | + "metadata": {}, |
| 285 | + "source": [ |
| 286 | + "## Access mover's backend services directly via the RPC classes" |
| 287 | + ] |
| 288 | + }, |
| 289 | + { |
| 290 | + "cell_type": "code", |
| 291 | + "execution_count": null, |
| 292 | + "id": "9144f17e", |
| 293 | + "metadata": {}, |
| 294 | + "outputs": [], |
| 295 | + "source": [ |
| 296 | + "# mover.bot\n", |
| 297 | + "# mover.slam\n", |
| 298 | + "# mover.nav\n", |
| 299 | + "# mover.cam" |
| 300 | + ] |
| 301 | + }, |
| 302 | + { |
| 303 | + "cell_type": "code", |
| 304 | + "execution_count": null, |
| 305 | + "id": "a019eda9", |
| 306 | + "metadata": {}, |
| 307 | + "outputs": [], |
| 308 | + "source": [] |
| 309 | + } |
| 310 | + ], |
| 311 | + "metadata": { |
| 312 | + "kernelspec": { |
| 313 | + "display_name": "Python 3 (ipykernel)", |
| 314 | + "language": "python", |
| 315 | + "name": "python3" |
| 316 | + }, |
| 317 | + "language_info": { |
| 318 | + "codemirror_mode": { |
| 319 | + "name": "ipython", |
| 320 | + "version": 3 |
| 321 | + }, |
| 322 | + "file_extension": ".py", |
| 323 | + "mimetype": "text/x-python", |
| 324 | + "name": "python", |
| 325 | + "nbconvert_exporter": "python", |
| 326 | + "pygments_lexer": "ipython3", |
| 327 | + "version": "3.8.13" |
| 328 | + } |
| 329 | + }, |
| 330 | + "nbformat": 4, |
| 331 | + "nbformat_minor": 5 |
| 332 | +} |
0 commit comments