From 13562c387cab63ec1054873972d5dcf3d06e3ab7 Mon Sep 17 00:00:00 2001 From: victorlouisdg Date: Mon, 12 Feb 2024 17:53:18 +0100 Subject: [PATCH] update rerun tutorial --- ...ed_tutorial.ipynb => rerun_tutorial.ipynb} | 73 ++++++++++--------- 1 file changed, 40 insertions(+), 33 deletions(-) rename airo-camera-toolkit/notebooks/{rerun_zed_tutorial.ipynb => rerun_tutorial.ipynb} (78%) diff --git a/airo-camera-toolkit/notebooks/rerun_zed_tutorial.ipynb b/airo-camera-toolkit/notebooks/rerun_tutorial.ipynb similarity index 78% rename from airo-camera-toolkit/notebooks/rerun_zed_tutorial.ipynb rename to airo-camera-toolkit/notebooks/rerun_tutorial.ipynb index ea170ca..08c048e 100644 --- a/airo-camera-toolkit/notebooks/rerun_zed_tutorial.ipynb +++ b/airo-camera-toolkit/notebooks/rerun_tutorial.ipynb @@ -6,7 +6,7 @@ "metadata": {}, "source": [ "# Rerun RGBD camera example\n", - "This example shows how to use [rerun](https://www.rerun.io/) for logging images, image annotations, point clouds, transforms between elements in the world, time-series in a way that you might want to do for a robotic manipulation setup. Make sure you have a **ZED2I camera connected**.\n", + "This example shows how to use [rerun](https://www.rerun.io/) for logging images, image annotations, point clouds, transforms between elements in the world, time-series in a way that you might want to do for a robotic manipulation setup. Make sure you have a **Realsense or ZED2I camera connected**.\n", "\n", "\n", "Rerun has more features such as logging meshes, logging 3D bboxes, URDFs (in process). Check the docs to learn more. \n", @@ -26,7 +26,6 @@ }, "outputs": [], "source": [ - "from airo_camera_toolkit.cameras.zed.zed2i import Zed2i\n", "import rerun as rr\n", "#autoreload\n", "%load_ext autoreload\n", @@ -41,7 +40,19 @@ "source": [ "# start rerun. If the UI is already running, it will connect to it. Otherwise it will start a new UI and connect to it.\n", "# you can also start rerun using `python -m rerun`.\n", - "rr.init(\"test\",spawn=True)" + "rr.init(\"test\", spawn=True)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "from airo_camera_toolkit.cameras.realsense.realsense import Realsense\n", + "\n", + "realsense = Realsense()\n", + "camera = realsense" ] }, { @@ -50,7 +61,10 @@ "metadata": {}, "outputs": [], "source": [ - "zed = Zed2i(depth_mode=Zed2i.NEURAL_DEPTH_MODE, resolution=Zed2i.RESOLUTION_2K)" + "from airo_camera_toolkit.cameras.zed.zed2i import Zed2i\n", + "\n", + "zed = Zed2i(depth_mode=Zed2i.NEURAL_DEPTH_MODE, resolution=Zed2i.RESOLUTION_2K)\n", + "camera = zed" ] }, { @@ -59,9 +73,9 @@ "metadata": {}, "outputs": [], "source": [ - "point_cloud = zed.get_colored_point_cloud()\n", - "rgb = zed.get_rgb_image()\n", - "depth = zed.get_depth_image()" + "point_cloud = camera.get_colored_point_cloud()\n", + "rgb = camera.get_rgb_image()\n", + "depth = camera.get_depth_image()" ] }, { @@ -71,7 +85,7 @@ "outputs": [], "source": [ "# log the colored point_cloud to the UI\n", - "rr.log(\"world/camera1/point_cloud\", rr.Points3D(positions=point_cloud.points,colors=point_cloud.colors))\n" + "rr.log(\"world/camera1/point_cloud\", rr.Points3D(positions=point_cloud.points, colors=point_cloud.colors))" ] }, { @@ -90,8 +104,8 @@ "outputs": [], "source": [ "# log the rgb and depth images to the UI in a new image/camera1 space, this will automatically become a 2D image viewer.\n", - "rr.log(\"image/camera1/rgb\",rr.Image(rgb))\n", - "rr.log(\"image/camera1/depth\",rr.Image(depth))" + "rr.log(\"image/camera1/rgb\", rr.Image(rgb))\n", + "rr.log(\"image/camera1/depth\", rr.Image(depth))" ] }, { @@ -100,8 +114,8 @@ "metadata": {}, "outputs": [], "source": [ - "# log a dummy 2D bbox \n", - "rr.log(\"image/camera1/rect\", rr.Boxes2D(mins=[20,100], sizes=[300,500]))" + "# log a dummy 2D bbox\n", + "rr.log(\"image/camera1/rect\", rr.Boxes2D(mins=[20, 100], sizes=[300, 500]))" ] }, { @@ -111,7 +125,10 @@ "outputs": [], "source": [ "# log some dummy keypoints and attach labels\n", - "rr.log(\"image/camera1/keypoints\", rr.Points2D([[600,500],[400,500]],keypoint_ids=[0,1],radii=20, labels=[\"keypoint1\",\"keypoint2\"]))" + "rr.log(\n", + " \"image/camera1/keypoints\",\n", + " rr.Points2D([[600, 500], [400, 500]], keypoint_ids=[0, 1], radii=20, labels=[\"keypoint1\", \"keypoint2\"]),\n", + ")" ] }, { @@ -120,10 +137,10 @@ "metadata": {}, "outputs": [], "source": [ - "# log dummy camera extrinsics from the world space. \n", + "# log dummy camera extrinsics from the world space.\n", "# This specifies the pose of camera in world.\n", - "translation = [0,0.5,0.7] \n", - "rotation = [-0.707,0,0,0.707] #scalar-last! \n", + "translation = [0, 0.5, 0.7]\n", + "rotation = [-0.707, 0, 0, 0.707] # scalar-last!\n", "# rr.log_rigid3(\"world/camera1\", parent_from_child=(translation, rotation))\n", "rr.log(\"world/camera1\", rr.Transform3D(translation=translation, rotation=rotation))" ] @@ -135,8 +152,8 @@ "outputs": [], "source": [ "# log the actual camera intrinsics, to create a pinhole camera model in the UI.\n", - "rr.log(\"world/camera1/rgb\", rr.Pinhole(image_from_camera=zed.intrinsics_matrix(), resolution=zed.resolution))\n", - "rr.log(\"world/camera1/rgb\",rr.Image(rgb))" + "rr.log(\"world/camera1/rgb\", rr.Pinhole(image_from_camera=camera.intrinsics_matrix(), resolution=camera.resolution))\n", + "rr.log(\"world/camera1/rgb\", rr.Image(rgb))" ] }, { @@ -145,7 +162,7 @@ "metadata": {}, "outputs": [], "source": [ - "# set up the 'view' of the 3D world space. This is for convenience so that rerun can sensible starting orientations for the spaces. \n", + "# set up the 'view' of the 3D world space. This is for convenience so that rerun can sensible starting orientations for the spaces.\n", "rr.log(\"world\", rr.ViewCoordinates.RIGHT_HAND_Z_UP, timeless=True)\n", "rr.log(\"world/camera1\", rr.ViewCoordinates.RDF, timeless=True)" ] @@ -158,8 +175,8 @@ "source": [ "# log some more data\n", "for _ in range(5):\n", - " point_cloud = zed.get_colored_point_cloud()\n", - " rr.log(\"world/camera1/point_cloud\", rr.Points3D(positions=point_cloud.points,colors=point_cloud.colors))" + " point_cloud = camera.get_colored_point_cloud()\n", + " rr.log(\"world/camera1/point_cloud\", rr.Points3D(positions=point_cloud.points, colors=point_cloud.colors))" ] }, { @@ -170,17 +187,7 @@ "source": [ "# log time-series (e.g. F/T sensor)\n", "for i in range(100):\n", - " rr.log(\"world/robot/force\",rr.TimeSeriesScalar(i))\n" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "# close the camera\n", - "zed.camera.close()" + " rr.log(\"world/robot/force\", rr.TimeSeriesScalar(i))" ] }, { @@ -210,7 +217,7 @@ "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython3", - "version": "3.10.13" + "version": "3.9.18" }, "vscode": { "interpreter": {