Skip to content

Commit

Permalink
Add example for realsense camera
Browse files Browse the repository at this point in the history
  • Loading branch information
haixuanTao committed Dec 6, 2024
1 parent f44745a commit 7ae1f80
Show file tree
Hide file tree
Showing 4 changed files with 30 additions and 9 deletions.
2 changes: 1 addition & 1 deletion examples/realsense/camera.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@ nodes:
tick: dora/timer/millis/20
outputs:
- image
- depth_image
- depth
env:
IMAGE_WIDTH: 640
IMAGE_HEIGHT: 480
Expand Down
20 changes: 20 additions & 0 deletions examples/realsense/camera_rerun.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
nodes:
- id: camera
build: pip install -e ../../node-hub/dora-pyrealsense
path: dora-pyrealsense
inputs:
tick: dora/timer/millis/20
outputs:
- image
- depth
env:
IMAGE_WIDTH: 640
IMAGE_HEIGHT: 480

- id: plot
build: pip install -e ../../node-hub/dora-rerun
path: dora-rerun
inputs:
image: camera/image
world/camera/depth: camera/depth

13 changes: 7 additions & 6 deletions node-hub/dora-pyrealsense/dora_pyrealsense/main.py
Original file line number Diff line number Diff line change
Expand Up @@ -43,9 +43,9 @@ def main():

depth_sensor = profile.get_device().first_depth_sensor()
depth_scale = depth_sensor.get_depth_scale()
rgb_profile = profile.get_stream(rs.stream.color)
depth_profile = profile.get_stream(rs.stream.depth)
rgb_intr = rgb_profile.as_video_stream_profile().get_intrinsics()
# rgb_profile = profile.get_stream(rs.stream.color)
# depth_profile = profile.get_stream(rs.stream.depth)
# rgb_intr = rgb_profile.as_video_stream_profile().get_intrinsics()
# rgb_intr = depth_profile.get_extrinsics_to(rgb_profile)
node = Node()
start_time = time.time()
Expand Down Expand Up @@ -110,9 +110,10 @@ def main():
continue

storage = pa.array(frame.ravel())
# metadata["resolution"] = [rgb_intr.width, rgb_intr.height]
# metadata["focal_length"] = [rgb_intr.fx, rgb_intr.fy]
# metadata["principal_point"] = [rgb_intr.ppx, rgb_intr.ppy]

# metadata["resolution"] = [int(rgb_intr.width), int(rgb_intr.height)]
# metadata["focal_length"] = [int(rgb_intr.fx), int(rgb_intr.fy)]
# metadata["principal_point"] = [int(rgb_intr.ppx), int(rgb_intr.ppy)]
node.send_output("image", storage, metadata)
node.send_output(
"depth", pa.array(scaled_depth_image.ravel()), metadata
Expand Down
4 changes: 2 additions & 2 deletions node-hub/dora-rerun/src/lib.rs
Original file line number Diff line number Diff line change
Expand Up @@ -164,12 +164,12 @@ pub fn lib_main() -> Result<()> {
.with_colormap(rerun::components::Colormap::Inferno);

rec.log(
"world/camera",
id.as_str().replace("/depth", ""),
&rerun::Pinhole::from_focal_length_and_resolution(&[605., 605.], &[640., 480.]),
)?;

// If we log a pinhole camera model, the depth gets automatically back-projected to 3D
rec.log("world/camera/depth", &depth_image)?;
rec.log(id.as_str(), &depth_image)?;
} else if id.as_str().contains("text") {
let buffer: StringArray = data.to_data().into();
buffer.iter().try_for_each(|string| -> Result<()> {
Expand Down

0 comments on commit 7ae1f80

Please sign in to comment.