gz-sensors icon indicating copy to clipboard operation
gz-sensors copied to clipboard

Gazebo Harmonic RGBD Camera: PointCloud and Depth Data Misaligned

Open miccol opened this issue 3 months ago • 7 comments
trafficstars

Note 1 I posted this question on Robotics Stackexchange last week, sorry for reposting here

Note 2 I created a repo with a minimal, reproducible example to help investigate the suspected issue https://github.com/miccol/rgbd_camera_issue

I'm using the rgbd_camera plugin in Gazebo Harmonic with ROS 2 and ros_gz_bridge to visualize RGB and depth data in RViz.

Here's my setup:

  • OS: Ubuntu 22.04
  • ROS 2: Jazzy
  • Gazebo: Harmonic 8.9.0

The setup publishes the following topics:

  • /rgbd_camera/camera_info (sensor_msgs/CameraInfo)
  • /rgbd_camera/depth_image (sensor_msgs/Image)
  • /rgbd_camera/image (sensor_msgs/Image)
  • /rgbd_camera/points (sensor_msgs/PointCloud2)

The (Potential) Issue

Although both /camera_info and /points have the same frame_id (rgbd_camera_link), in RViz the camera pyramid (from CameraInfo) and the PointCloud2 are visually misaligned.

The point cloud appears skewed or offset from the expected camera frustum. All TFs are valid, and static transforms are correctly set.

enter image description here

screenshot

What I've Checked

  • Confirmed both messages use the same frame_id
  • TF tree is consistent and stable
  • RViz Fixed Frame is world
  • Camera is static and aligned properly
  • RGB image renders fine
  • PointCloud renders fine
  • CameraInfo renders fine

My Hypothesis

There may be a mismatch in the projection model used internally by the rgbd_camera plugin to compute the point cloud vs. what's reported in /camera_info.

Alternatively, it could be a bug in how Gazebo Harmonic or ros_gz_bridge constructs the PointCloud2 message.


Question:

Has anyone seen this misalignment issue between camera_info and point clouds from rgbd_camera in Gazebo Harmonic?

Could this be due to an internal projection inconsistency or a known bug in gz-sensors? It looks like that, recently, someone else had a similar issue https://github.com/gazebosim/gz-sensors/issues/29#issuecomment-3113732696

https://github.com/moveit/moveit2/issues/3042

Thanks

MC

miccol avatar Aug 06 '25 17:08 miccol

I think I have defined in my own URDF models two frames with permuted axis due to this same exact problem. Camera a is should be Z axis, but Gazebo uses X or Y IIRC, or at least this is what I experienced. Tomorrow I may confirm this / post more after re-checking.

roncapat avatar Aug 06 '25 18:08 roncapat

@miccol I confirm I need to define a frame rotated w.r.t. the ROS-convention compliant frame as such:

  <link name="camera_frame" />
  <link name="rotated_camera_frame" />

  <joint name = "rotated_camera_frame_joint" type="fixed">
        <parent link="camera_frame" />
        <child link="rotated_camera_frame" />
        <origin xyz="0.0 0.0 0.0" rpy="0 -${pi/2} ${pi/2}" />
  </joint>

Of course, I believe that this should be fixed. Gazebo and ROS 2 IMHO shall adhere to the same camera frame conventions.

roncapat avatar Aug 16 '25 11:08 roncapat

Hi @miccol,

I am observing the same issue as you faced, have you found any solution yet ?

mathanprasannakumar avatar Sep 23 '25 01:09 mathanprasannakumar

Hi @mathanprasannakumar I did what @roncapat suggested

miccol avatar Sep 23 '25 16:09 miccol

BTW, I think this deserves a fix rather than a workaround...

roncapat avatar Sep 23 '25 16:09 roncapat

@roncapat , Could you please explain what kind of rotation that we are applying to achieve what , because in the issue the camera frustum is facing towards the z axis of the link defined and for the point cloud is observed along the x axis of the link.

mathanprasannakumar avatar Sep 24 '25 02:09 mathanprasannakumar

@miccol I confirm I need to define a frame rotated w.r.t. the ROS-convention compliant frame as such:

Of course, I believe that this should be fixed. Gazebo and ROS 2 IMHO shall adhere to the same camera frame conventions.

Could you explain how you rotate the origin camera frame and attach to the optical frame? I tried it but it doesn't work, the PointCloud2 and DepthCloud is still misaligned.

XHao1997 avatar Sep 27 '25 06:09 XHao1997