Multiple ROS cameras with Python API - Only one publishing

I am trying to create multiple cameras, each publishing to different ROS topics, with the Python API. Specifically, I am calling:

    def create_camera(self, args=None):
        print("Executing CreatePrimWithDefaultXform")
        status, _ = omni.kit.commands.execute(
            "CreatePrimWithDefaultXform",
            prim_type="Camera",
            prim_path="/sim_camera",
            attributes={
                "focusDistance": 400,
                "focalLength": 24
            },
        )
        print("Complete: " + str(status))
        self.viewport.set_active_camera("/sim_camera")

        # Set Camera Pose
        print("Executing TransformPrimCommand")
        status, _ = omni.kit.commands.execute("TransformPrimCommand",
                                              path="/sim_camera",
                                              new_transform_matrix=Gf.Matrix4d(
                                                  -0.642788,
                                                  0.766045,
                                                  0.0,
                                                  0.0,
                                                  -0.133022,
                                                  -0.111619,
                                                  0.984807,
                                                  0.0,
                                                  0.754407,
                                                  0.633022,
                                                  0.173648,
                                                  0.0,
                                                  175.0,
                                                  150.0,
                                                  70.0,
                                                  1.0,
                                              ))
        print("Complete: " + str(status))

        # adding camera topic
        print("Executing ROSBridgeCreateCamera")
        status, prim = omni.kit.commands.execute(
            "ROSBridgeCreateCamera",
            path="/ROS_Camera",
            enabled=True,
            resolution=Gf.Vec2i(1280, 720),
            frame_id="sim_camera",
            camera_info_topic="/camera_info",
            rgb_enabled=True,
            rgb_topic="/rgb",
            depth_enabled=True,
            depth_topic="/depth",
            segmentation_enabled=False,
            semantic_topic="/semantic",
            instance_topic="/instance",
            label_topic="/label",
            bbox2d_enabled=False,
            bbox2d_topic="/bbox_2d",
            bbox3d_enabled=False,
            bbox3d_topic="/bbox_3d",
            queue_size=10,
            camera_prim_rel=["/sim_camera"],
        )
        print("Complete: " + str(status))

    def create_camera2(self, args=None):
        print("Executing CreatePrimWithDefaultXform")
        status, _ = omni.kit.commands.execute(
            "CreatePrimWithDefaultXform",
            prim_type="Camera",
            prim_path="/sim_camera_2",
            attributes={
                "focusDistance": 400,
                "focalLength": 24
            },
        )
        print("Complete: " + str(status))
        self.viewport.set_active_camera("/sim_camera_2")

        # Set Camera Pose
        print("Executing TransformPrimCommand")
        status, _ = omni.kit.commands.execute("TransformPrimCommand",
                                              path="/sim_camera_2",
                                              new_transform_matrix=Gf.Matrix4d(
                                                  -0.642788,
                                                  0.766045,
                                                  0.0,
                                                  0.0,
                                                  -0.133022,
                                                  -0.111619,
                                                  0.984807,
                                                  0.0,
                                                  0.754407,
                                                  0.633022,
                                                  0.173648,
                                                  0.0,
                                                  -175.0,
                                                  -150.0,
                                                  70.0,
                                                  1.0,
                                              ))
        print("Complete: " + str(status))

        # adding camera topic
        print("Executing ROSBridgeCreateCamera")
        status, prim = omni.kit.commands.execute(
            "ROSBridgeCreateCamera",
            path="/ROS_Camera_2",
            enabled=True,
            resolution=Gf.Vec2i(1280, 720),
            frame_id="sim_camera_2",
            camera_info_topic="/camera_info_2",
            rgb_enabled=True,
            rgb_topic="/rgb_2",
            depth_enabled=True,
            depth_topic="/depth_2",
            segmentation_enabled=False,
            semantic_topic="/semantic",
            instance_topic="/instance",
            label_topic="/label",
            bbox2d_enabled=False,
            bbox2d_topic="/bbox_2d",
            bbox3d_enabled=False,
            bbox3d_topic="/bbox_3d",
            queue_size=10,
            camera_prim_rel=["/sim_camera_2"],
        )
        print("Complete: " + str(status))

Where create_camera2 is the exact same as create_camera, I just changed the names of the ROS topics, prim paths, etc, as well as where the camera is located. I copied this code structure from rostopics.py.

When I call these functions one after another, it creates both pairs of topics (/rgb, /rgb_2, /depth, /depth_2). Two viewport panels are also opened, one for each camera. However, data is only being published to the second topic.

If I only call one of the functions, then data is successfully published to just that camera’s corresponding topics, meaning I think both sets of code are correctly written.

Is there some way to get multi-camera ROS support working with the Python API?

If you press stop and play and then continue running, does this fix the issue?
There is a known issue with enabling cameras, that also occurs with the ROS stereo sample where you have to start/stop the sim.
https://docs.omniverse.nvidia.com/app_isaacsim/app_isaacsim/sample_ros_stereo.html

Also you shouldn’t need to set

self.viewport.set_active_camera("/sim_camera_2")

The ROS bridge camera component automatically assigns cameras to viewports. Does commenting that out make a difference?

1 Like

I added a Pure ROS sample for our bugfix release coming out in a week or so. Will add one for cameras as well and see if there are any issues that I missed.

1 Like

Yep, pressing stop and then play again allowed both cameras to publish! Is there a way to programatically do this in Python? Would it just be kit.stop() and kit.play() after calling the latter once to effectively restart it?

EDIT: Confirmed – this works. Thanks for the help!!!

1 Like