[Bug Report] Camera Pose doesn't update in IsaacLab 2.2.0
Despite adding the update_latest_camera_pose=True parameter to CameraCfg, camera pose still doesn't update. Tried instantiating the view myself and calling get_world_poses() but still doesn't change.
IsaacLab & IsaacSim were installed using pip. IsaacLab==2.2.0 IsaacSim==5.0.0
Thank you for posting this. Could you add steps to reproduce this? We are reviewing a summary posted earlier that may help. Will repost this soon.
Does update_latest_camera_pose affect the image data that the camera records during training?
For example, if in the "_get_observations" method of a DirectRLEnv you call something like "camera_data = self.robot_camera.data.output["rgb"] / 255.0", where self.robot_camera is defined as a TiledCamera with some TiledCameraCfg, does the data of self.robot_camera.data.output["rgb"] get affected if update_latest_camera_pose is True or False in TiledCameraCfg?
same issue,TiledCamera. After many simulation steps the on hand camera pose doesn't update.
my config:
CAMERA_CFG = TiledCameraCfg(
update_period=0,
height=CAM_HEIGHT,
width=CAM_WIDTH,
update_latest_camera_pose=True,
data_types=[*MODALITIES],
colorize_instance_id_segmentation=False,
colorize_semantic_segmentation=False,
colorize_instance_segmentation=False,
spawn=sim_utils.PinholeCameraCfg(
focal_length=focal_length_cm,
focus_distance=focus_distance,
horizontal_aperture=horizontal_aperture_mm,
clipping_range=(0.01, 1.0e5),
),
offset=TiledCameraCfg.OffsetCfg(pos=VIEW_POS_CAM if ON_HAND else VIEW_POS_W, rot=VIEW_QUAT_CAM, convention="ros"),
)
same issue here
Yeah, I was using the camera for mapping, and the orientation won't update. My fix was to rotate the initial pose by the pose of my robot. I was using a mobile robot, so it was relatively easy.
same issue. I found that the problem was caused by XFormPrim.get_world_poses() returning the same poses and quat every time. I thikn this is a BUG.
Meanwhile, the camera data capture seems to be normal. The depth map I visualized changes as the robot moves.
Thank you for following up. We would need clear steps to reproduce this. Please post an example we may use. Thank you.
Could you please try on Isaac sim 5.1, I just tested with the set up the with dexsuite environment using
num_cameras = sensor.data.intrinsic_matrices.size(0)
positions = torch.tensor([[2.5, 2.5, 2.5]], device=env.device).repeat(num_cameras, 1) + env.scene.env_origins
targets = torch.tensor([[0.0, 0.0, 0.0]], device=env.device).repeat(num_cameras, 1)
sensor.set_world_poses_from_view(positions, targets)
Before set poses
After set poses
@ooctipus @RandomOakForest
This script is modified based on scripts/tutorials/04_sensors/add_sensors_on_robot.py, and it can reproduce the bug.
Here is what I did:
-
Set
update_latest_camera_pose=Truefor theCamera. -
Added two additional
RayCasterCameras on top of the originalCamera:camera2is attached to{ENV_REGEX_NS}/Robot/basecamera3is attached to{ENV_REGEX_NS}/Robot/base/battery
-
Printed the
pos_wof all three cameras.
Since the robot dog moves up and down, all three cameras’ pos_w are expected to change accordingly.
However, in my observation:
camera1andcamera3positions remain constant.- Only
camera2’s position changes as expected.
The camera position updates always depend on self._view.get_world_poses(), i.e., the XFormPrim’s world transform updates.
It seems that for some reason, certain prims do not update their poses. This might be related to the prim hierarchy level or whether the prim is empty.
For the Camera sensor, a new prim is created in the scene, and its pose never updates — therefore, the Camera’s pos_w stays constant.
For the RayCasterCamera, its pose depends on the prim it is attached to:
- The prim for
camera2updates correctly. - The prim for
camera3does not update.
For the Camera sensor, this does not affect the captured image — the camera view still moves correctly even though pos_w remains static.
However, for the RayCasterCamera, this may impact data capture, since ray origins are computed based on the prim’s pose.
Environment details:
- Isaac Lab version: 2.2.0
- Isaac Sim version: 5.0.0
You can reproduce this issue by replacing the original scripts/tutorials/04_sensors/add_sensors_on_robot.py
with my modified script, then running the following command: ./isaaclab.sh -p scripts/tutorials/04_sensors/add_sensors_on_robot.py --num_envs 2 --enable_cameras
Additional information: I found that when the view is ArticulationView or RigidBodyView, it works fine. But XFormPrim.get_world_poses() always returns the same position. (Added on 16.Oct)
# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md).
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""
This script demonstrates how to add and simulate on-board sensors for a robot.
We add the following sensors on the quadruped robot, ANYmal-C (ANYbotics):
* USD-Camera: This is a camera sensor that is attached to the robot's base.
* Height Scanner: This is a height scanner sensor that is attached to the robot's base.
* Contact Sensor: This is a contact sensor that is attached to the robot's feet.
.. code-block:: bash
# Usage
./isaaclab.sh -p scripts/tutorials/04_sensors/add_sensors_on_robot.py --enable_cameras
"""
"""Launch Isaac Sim Simulator first."""
import argparse
from isaaclab.app import AppLauncher
# add argparse arguments
parser = argparse.ArgumentParser(description="Tutorial on adding sensors on a robot.")
parser.add_argument("--num_envs", type=int, default=2, help="Number of environments to spawn.")
# append AppLauncher cli args
AppLauncher.add_app_launcher_args(parser)
# parse the arguments
args_cli = parser.parse_args()
# launch omniverse app
app_launcher = AppLauncher(args_cli)
simulation_app = app_launcher.app
"""Rest everything follows."""
import torch
import isaaclab.sim as sim_utils
from isaaclab.assets import ArticulationCfg, AssetBaseCfg
from isaaclab.scene import InteractiveScene, InteractiveSceneCfg
from isaaclab.sensors import CameraCfg, ContactSensorCfg, RayCasterCfg, patterns
from isaaclab.utils import configclass
from isaaclab.sensors import RayCasterCameraCfg
##
# Pre-defined configs
##
from isaaclab_assets.robots.anymal import ANYMAL_C_CFG # isort: skip
@configclass
class SensorsSceneCfg(InteractiveSceneCfg):
"""Design the scene with sensors on the robot."""
# ground plane
ground = AssetBaseCfg(prim_path="/World/defaultGroundPlane", spawn=sim_utils.GroundPlaneCfg())
# lights
dome_light = AssetBaseCfg(
prim_path="/World/Light", spawn=sim_utils.DomeLightCfg(intensity=3000.0, color=(0.75, 0.75, 0.75))
)
# robot
robot: ArticulationCfg = ANYMAL_C_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")
# sensors
camera1 = CameraCfg(
prim_path="{ENV_REGEX_NS}/Robot/base/front_cam",
update_period=0.1,
height=480,
width=640,
data_types=["rgb", "distance_to_image_plane"],
spawn=sim_utils.PinholeCameraCfg(
focal_length=24.0, focus_distance=400.0, horizontal_aperture=20.955, clipping_range=(0.1, 1.0e5)
),
offset=CameraCfg.OffsetCfg(pos=(0.510, 0.0, 0.015), rot=(0.5, -0.5, 0.5, -0.5), convention="ros"),
update_latest_camera_pose=True,
)
camera2 = RayCasterCameraCfg(
prim_path="{ENV_REGEX_NS}/Robot/base",
mesh_prim_paths=["/World/defaultGroundPlane"],
update_period=0.1,
offset=RayCasterCameraCfg.OffsetCfg(pos=(0.510, 0.0, 0.015), rot=(0.5, -0.5, 0.5, -0.5), convention="ros"),
data_types=["distance_to_image_plane"],
debug_vis=False,
pattern_cfg=patterns.PinholeCameraPatternCfg(
focal_length=24.0,
horizontal_aperture=20.955,
height=480,
width=640,
),
)
camera3 = RayCasterCameraCfg(
prim_path="{ENV_REGEX_NS}/Robot/base/battery",
mesh_prim_paths=["/World/defaultGroundPlane"],
update_period=0.1,
offset=RayCasterCameraCfg.OffsetCfg(pos=(0.510, 0.0, 0.015), rot=(0.5, -0.5, 0.5, -0.5), convention="ros"),
data_types=["distance_to_image_plane"],
debug_vis=False,
pattern_cfg=patterns.PinholeCameraPatternCfg(
focal_length=24.0,
horizontal_aperture=20.955,
height=480,
width=640,
),
)
height_scanner = RayCasterCfg(
prim_path="{ENV_REGEX_NS}/Robot/base",
update_period=0.02,
offset=RayCasterCfg.OffsetCfg(pos=(0.0, 0.0, 20.0)),
ray_alignment="yaw",
pattern_cfg=patterns.GridPatternCfg(resolution=0.1, size=[1.6, 1.0]),
debug_vis=True,
mesh_prim_paths=["/World/defaultGroundPlane"],
)
contact_forces = ContactSensorCfg(
prim_path="{ENV_REGEX_NS}/Robot/.*_FOOT", update_period=0.0, history_length=6, debug_vis=True
)
def run_simulator(sim: sim_utils.SimulationContext, scene: InteractiveScene):
"""Run the simulator."""
# Define simulation stepping
sim_dt = sim.get_physics_dt()
sim_time = 0.0
count = 0
# Simulate physics
while simulation_app.is_running():
# Reset
if count % 500 == 0:
# reset counter
count = 0
# reset the scene entities
# root state
# we offset the root state by the origin since the states are written in simulation world frame
# if this is not done, then the robots will be spawned at the (0, 0, 0) of the simulation world
root_state = scene["robot"].data.default_root_state.clone()
root_state[:, :3] += scene.env_origins
scene["robot"].write_root_pose_to_sim(root_state[:, :7])
scene["robot"].write_root_velocity_to_sim(root_state[:, 7:])
# set joint positions with some noise
joint_pos, joint_vel = (
scene["robot"].data.default_joint_pos.clone(),
scene["robot"].data.default_joint_vel.clone(),
)
joint_pos += torch.rand_like(joint_pos) * 0.1
scene["robot"].write_joint_state_to_sim(joint_pos, joint_vel)
# clear internal buffers
scene.reset()
print("[INFO]: Resetting robot state...")
# Apply default actions to the robot
# -- generate actions/commands
targets = scene["robot"].data.default_joint_pos
# -- apply action to the robot
scene["robot"].set_joint_position_target(targets)
# -- write data to sim
scene.write_data_to_sim()
# perform step
sim.step()
# update sim-time
sim_time += sim_dt
count += 1
# update buffers
scene.update(sim_dt)
# print information from the sensors
print("-------------------------------")
print("The position of camera1:", scene["camera1"].data.pos_w)
print("The position of camera2:", scene["camera2"].data.pos_w)
print("The position of camera3:", scene["camera3"].data.pos_w)
print("-------------------------------")
def main():
"""Main function."""
# Initialize the simulation context
sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device)
sim = sim_utils.SimulationContext(sim_cfg)
# Set main camera
sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0])
# Design scene
scene_cfg = SensorsSceneCfg(num_envs=args_cli.num_envs, env_spacing=2.0)
scene = InteractiveScene(scene_cfg)
# Play the simulator
sim.reset()
# Now we are ready!
print("[INFO]: Setup complete...")
# Run the simulator
run_simulator(sim, scene)
if __name__ == "__main__":
# run the main function
main()
# close sim app
simulation_app.close()
Despite adding the
update_latest_camera_pose=Trueparameter to CameraCfg, camera pose still doesn't update. Tried instantiating the view myself and callingget_world_poses()but still doesn't change.IsaacLab & IsaacSim were installed using pip. IsaacLab==2.2.0 IsaacSim==5.0.0
Same versions and same issue, the image captured from the camera looks fine when changing pose, but the camera.data.pos_w does not change. The camera.data.pos_w was printed after simulation step and scene update.
Let me take a look at this
Having the same issue... any update on this?
Same issue... any update?