Cannot set Viewport resolution in one time with Python REPL

I try to launch camera to subscribe an image from ROS 2.
I am using Python REPL to launch camera.
I cannot set Viewport resolution, when I launch a script with Python REPL.
But I can set Viewport resolution with another terminal after the script launched.

You can see the script in following repository.

How can I set Viewport resolution in one time?

Hi @hijimasa - It will be difficult for Devs to go through these long code. Can you provide narrow down version of code chunk where you are seeing issues?

Hi @rthaker

I make small example.

import math
import omni.kit.commands

import omni
from omni.isaac.core.utils import stage
from omni.isaac.core.utils.render_product import create_hydra_texture
import omni.kit.viewport.utility
from pxr import UsdGeom
import omni.graph.core as og
from omni.isaac.core.utils.prims import set_targets
from omni.kit.viewport.utility import get_viewport_from_window_name

Frame_per_Second = 60.0

image_height = 600
image_width = 600
aspect_ratio = float(image_width) / float(image_height)
horizontal_fov_rad = 1.3962634
horizontal_focal_length = 30
vertical_focal_length = 30
focus_distance = 400

horizontal_aperture = math.tan(horizontal_fov_rad / 2.0) * 2.0 * horizontal_focal_length
vertical_aperture = math.tan(horizontal_fov_rad / aspect_ratio / 2.0) * 2.0 * vertical_focal_length

camera_prim = UsdGeom.Camera(omni.usd.get_context().get_stage().DefinePrim("/World/Camera", "Camera"))
xform_api = UsdGeom.XformCommonAPI(camera_prim)
xform_api.SetTranslate(Gf.Vec3d(0, 0, 0))
xform_api.SetRotate((90, 0, -90), UsdGeom.XformCommonAPI.RotationOrderXYZ)
camera_prim.GetHorizontalApertureAttr().Set(horizontal_aperture)
camera_prim.GetVerticalApertureAttr().Set(vertical_aperture)
camera_prim.GetProjectionAttr().Set("perspective")
camera_prim.GetFocalLengthAttr().Set(horizontal_focal_length)
camera_prim.GetFocusDistanceAttr().Set(focus_distance)
camera_prim.GetClippingRangeAttr().Set((0.02, 300.0))

keys = og.Controller.Keys
(ros_camera_graph, _, _, _) = og.Controller.edit(
    {
        "graph_path": "/World/Camera_Graph",
        "evaluator_name": "push",
        "pipeline_stage": og.GraphPipelineStage.GRAPH_PIPELINE_STAGE_ONDEMAND,
    },
    {
        keys.CREATE_NODES: [
            ("OnTick", "omni.graph.action.OnTick"),
            ("createViewport", "omni.isaac.core_nodes.IsaacCreateViewport"),
            ("getRenderProduct", "omni.isaac.core_nodes.IsaacGetViewportRenderProduct"),
            ("setCamera", "omni.isaac.core_nodes.IsaacSetCameraOnRenderProduct"),
            ("cameraHelperRgb", "omni.isaac.ros2_bridge.ROS2CameraHelper"),
            ("cameraHelperInfo", "omni.isaac.ros2_bridge.ROS2CameraHelper"),
        ],
        keys.CONNECT: [
            ("OnTick.outputs:tick", "createViewport.inputs:execIn"),
            ("createViewport.outputs:execOut", "getRenderProduct.inputs:execIn"),
            ("createViewport.outputs:viewport", "getRenderProduct.inputs:viewport"),
            ("getRenderProduct.outputs:execOut", "setCamera.inputs:execIn"),
            ("getRenderProduct.outputs:renderProductPath", "setCamera.inputs:renderProductPath"),
            ("setCamera.outputs:execOut", "cameraHelperRgb.inputs:execIn"),
            ("setCamera.outputs:execOut", "cameraHelperInfo.inputs:execIn"),
            ("getRenderProduct.outputs:renderProductPath", "cameraHelperRgb.inputs:renderProductPath"),
            ("getRenderProduct.outputs:renderProductPath", "cameraHelperInfo.inputs:renderProductPath"),
        ],
        keys.SET_VALUES: [
            ("createViewport.inputs:viewportId", 1),
            ("createViewport.inputs:name", "/World/Viewport"),
            ("cameraHelperRgb.inputs:frameId", "Camera"),
            ("cameraHelperRgb.inputs:topicName", "World/image_raw"),
            ("cameraHelperRgb.inputs:type", "rgb"),
            ("cameraHelperInfo.inputs:frameId", "Camera"),
            ("cameraHelperInfo.inputs:topicName", "/World/camera_info"),
            ("cameraHelperInfo.inputs:type", "camera_info"),
        ],
    },
)

set_targets(
    prim=stage.get_current_stage().GetPrimAtPath("/World/Camera_Graph" + "/setCamera"),
    attribute="inputs:cameraPrim",
    target_prim_paths=["/World/Camera"],
)

og.Controller.evaluate_sync(ros_camera_graph)

viewport_api = get_viewport_from_window_name("/World/Viewport")
viewport_api.set_texture_resolution((image_width, image_height))

Please save above to test.py, and you can launch by following command.

(sleep 1; cat test.py; sleep 20) | telnet localhost 8223

Please enable extentions, omni.isaac.ros2_bridge and omni.isaac.repl before launching above command.

The viewport is launched by above command, but the viewport resolution is not changed.

I solved this problem by following code.

import math
import omni.kit.commands

import omni
from omni.isaac.core.utils import stage
from omni.isaac.core.utils.render_product import create_hydra_texture
import omni.kit.viewport.utility
from pxr import UsdGeom
import omni.graph.core as og
from omni.isaac.core.utils.prims import set_targets
from omni.kit.viewport.utility import get_viewport_from_window_name

Frame_per_Second = 60.0

image_height = 600
image_width = 600
aspect_ratio = float(image_width) / float(image_height)
horizontal_fov_rad = 1.3962634
horizontal_focal_length = 30
vertical_focal_length = 30
focus_distance = 400

horizontal_aperture = math.tan(horizontal_fov_rad / 2.0) * 2.0 * horizontal_focal_length
vertical_aperture = math.tan(horizontal_fov_rad / aspect_ratio / 2.0) * 2.0 * vertical_focal_length

camera_prim = UsdGeom.Camera(omni.usd.get_context().get_stage().DefinePrim("/World/Camera", "Camera"))
xform_api = UsdGeom.XformCommonAPI(camera_prim)
xform_api.SetTranslate(Gf.Vec3d(0, 0, 0))
xform_api.SetRotate((90, 0, -90), UsdGeom.XformCommonAPI.RotationOrderXYZ)
camera_prim.GetHorizontalApertureAttr().Set(horizontal_aperture)
camera_prim.GetVerticalApertureAttr().Set(vertical_aperture)
camera_prim.GetProjectionAttr().Set("perspective")
camera_prim.GetFocalLengthAttr().Set(horizontal_focal_length)
camera_prim.GetFocusDistanceAttr().Set(focus_distance)
camera_prim.GetClippingRangeAttr().Set((0.02, 300.0))

keys = og.Controller.Keys
(ros_camera_graph, _, _, _) = og.Controller.edit(
    {
        "graph_path": prim_path + "/Camera_Graph",
        "evaluator_name": "push",
        "pipeline_stage": og.GraphPipelineStage.GRAPH_PIPELINE_STAGE_ONDEMAND,
    },
    {
        keys.CREATE_NODES: [
            ("OnTick", "omni.graph.action.OnTick"),
            ("createRenderProduct", "omni.isaac.core_nodes.IsaacCreateRenderProduct"),
            ("cameraHelperRgb", "omni.isaac.ros2_bridge.ROS2CameraHelper"),
            ("cameraHelperInfo", "omni.isaac.ros2_bridge.ROS2CameraHelper"),
        ],
        keys.CONNECT: [
            ("OnTick.outputs:tick", "createRenderProduct.inputs:execIn"),
            ("createRenderProduct.outputs:execOut", "cameraHelperRgb.inputs:execIn"),
            ("createRenderProduct.outputs:execOut", "cameraHelperInfo.inputs:execIn"),
            ("createRenderProduct.outputs:renderProductPath", "cameraHelperRgb.inputs:renderProductPath"),
            ("createRenderProduct.outputs:renderProductPath", "cameraHelperInfo.inputs:renderProductPath"),
        ],
        keys.SET_VALUES: [
            ("createRenderProduct.inputs:cameraPrim", prim_path + "/Camera"),
            ("createRenderProduct.inputs:enabled", True),
            ("createRenderProduct.inputs:height", image_height),
            ("createRenderProduct.inputs:width", image_width),
            ("cameraHelperRgb.inputs:frameId", child.attrib["name"]),
            ("cameraHelperRgb.inputs:topicName", prim_path + "/" + child.find("topic").text),
            ("cameraHelperRgb.inputs:type", "rgb"),
            ("cameraHelperInfo.inputs:frameId", child.attrib["name"]),
            ("cameraHelperInfo.inputs:topicName", prim_path + "/camera_info"),
            ("cameraHelperInfo.inputs:type", "camera_info"),
        ],
    },
)

og.Controller.evaluate_sync(ros_camera_graph)

This topic was automatically closed 14 days after the last reply. New replies are no longer allowed.