1
$\begingroup$

I am simulating a quadrotor with a depth camera on Gazebo and I am trying to see the data published by the simulation on RViz2.

The problem is that when I tried to visualize the point cloud of the camera from the fixed frame "map": I got the error message

Message Filter dropping message: frame 'camera_link' at time 1675148130.527 for reason 'Unknown'

As far as I understood, this error message is associated with the inability of RViz to find the transformation from the static frame "map" to the frame "camera_link". So, I started playing a bit around, trying to understand what was happening.

I was publishing 3 transformations through a ROS2 node:

  • "map" to "odom" (static tf)
  • "odom" to "drone" (dynamic tf)
  • "drone" to "camera_link" (static tf) All of them were being published simultaneously at the same timestamps.

I was able to see all the transformations correctly published on the topics /tf_static and /tf through the command

ros2 topic echo <topic_name>

Moreover, I was able to visualize them in RViz2 using the TF tool, all of them connected in the three as reported in the above list. So RViz2 can correctly read them, and I was able to select each of the 4 four frames as the fixed frame. So I started changing the fixed frame to see if anything happened.

When I selected either "drone" or "camera_link" as the fixed frame, I was able to visualize the point cloud of the camera. When I selected either "map" or "odom" I got the error message.

My conclusion, for now, is that there could be some problems I am not aware of when using dynamic tf in RViz or when mixing static and dynamic tf.

I was not able to find a solution looking on the web, so I hoped some of you could help me in debugging this issue.

$\endgroup$
3
  • $\begingroup$ I opened the same issue on the RViz2 GitHub page github.com/ros2/rviz/issues/1050 $\endgroup$ Commented Aug 25, 2023 at 15:45
  • $\begingroup$ Do you get just a few of these error messages at startup, or do they happen a lot? Are both the drone and the laptop using NTP to maintain an accurate time-of-day clock? $\endgroup$
    – Mike973
    Commented Aug 26, 2023 at 12:21
  • $\begingroup$ The error messages are spawned continuously when trying to visualize the PointCloud from "map" or "odom". The drone for now is just simulated on Gazebo, it is not a real drone. $\endgroup$ Commented Aug 26, 2023 at 18:01

1 Answer 1

1
$\begingroup$

If you are using simulation, the ros time is the 'number of seconds since simulation start'.

However, the timestamp in your error message is much too large ("time 1675148130.527") for that, which indicates you did not set the use_sim_time ros parameter in all of your ros nodes.

$\endgroup$
1
  • $\begingroup$ That was it! Thank you very much, you saved me hours of headaches :) $\endgroup$ Commented Aug 28, 2023 at 9:29

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.

Not the answer you're looking for? Browse other questions tagged or ask your own question.