ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Rviz2 can't visualize image from Gazebo

asked 2021-04-19 11:46:39 -0500

Zero39 gravatar image

Hello, I'm using Ubuntu 20.04 with Ros Foxy and I'm trying to visualize in Rviz2 the images captured by a camera in Gazebo attached to a drone. I have the following tree frames:

  • odom_frame
    • drone
      • robot_camera_link

The transformation between drone and odom_frame is supplied by a Ros2 node, while the transformation between drone and robot_camera_link is given through the command ros2 run tf2_ros static_transform_publisher 0.2 0 0 0 0 0 drone robot_camera_link; so far everything works and in Rviz I can correctly visualize the three frames.

After adding the image plugin and setting the QoS policies as required by the publisher, Rviz doesn't show the image and on the terminal is continuously printed the message

[rviz]: Message Filter dropping message: frame 'robot_camera_link' at time ... for reason 'Unknown'

I managed to get the right image in just two cases:

  • running ros2 run tf2_ros static_transform_publisher 0.2 0 0 0 0 0 **odom_frame** robot_camera_link, so attaching the frame of the camera directly to the fixed frame, or
  • changing the Fixed Frame parameter to drone instead of odom_frame

So it seems as the plugin must always be attached to the fixed frame to be properly visualized, but I'm sure it's not and I'm certainly doing something wrong that I can't figure out.

You can find below the SDF files I'm using.

Please let me know if you need further info.

Thank you very much for your help.

<?xml version='1.0'?>
<sdf version='1.5'>
  <model name='iris_fpv_cam'>

    <include>
      <uri>model://iris</uri>
    </include>

    <include>
      <uri>model://fpv_cam</uri>
      <pose>0.2 0 0 0 0 0</pose>
    </include>
    <joint name="fpv_cam_joint" type="fixed">
      <child>fpv_cam::link</child>
      <parent>iris::base_link</parent>
      <axis>
        <xyz>0 0 1</xyz>
        <limit>
          <upper>0</upper>
          <lower>0</lower>
        </limit>
      </axis>
    </joint>

  </model>
</sdf>

////////////////////////////////////////////////////////////////////////////

<?xml version='1.0'?>
<sdf version='1.6'>
    <model name='fpv_cam'>
      <pose>-0.158979 -0.04405 0.045074 0 -0 0</pose>
      <link name='link'>
        <inertial>
          <mass>0.015</mass>
          <inertia>
            <ixx>4.15e-6</ixx>
            <ixy>0</ixy>
            <ixz>0</ixz>
            <iyy>2.407e-6</iyy>
            <iyz>0</iyz>
            <izz>2.407e-6</izz>
          </inertia>
        </inertial>
        <collision name='collision'>
          <geometry>
            <box>
              <size>0.01 0.01 0.01</size>
            </box>
          </geometry>
          <max_contacts>10</max_contacts>
          <surface>
            <contact>
              <ode/>
            </contact>
            <bounce/>
            <friction>
              <ode/>
            </friction>
          </surface>
        </collision>
        <visual name='visual'>
          <geometry>
            <box>
              <size>0.01 0.01 0.01</size>
            </box>
          </geometry>
        </visual>

        <sensor name='camera' type='camera'>

          <update_rate>30.0</update_rate>
          <always_on>1</always_on>
          <visualize>1</visualize>
          <camera name="camera">
            <horizontal_fov>1.3962634</horizontal_fov>
            <image>
              <width>800</width>
              <height>800</height>
              <format>R8G8B8</format>
            </image>
            <clip>
              <near>0.02</near>
              <far>300</far>
            </clip>
            <distortion>
              <k1>0.0</k1>
              <k2>0.0</k2>
              <k3>0.0</k3>
              <p1>0.0</p1>
              <p2>0.0</p2>
              <center>0.5 0.5</center>
            </distortion>
          </camera>
          <plugin filename="libgazebo_ros_camera.so" name="camera_controller">
            <ros>
              <namespace>/bocbot</namespace>
              <argument>camera/image_raw:=/bocbot/camera/image</argument>
              <argument>camera ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2021-04-20 02:11:30 -0500

Joe28965 gravatar image

Did you set the 'Reliability Policy' in RViz correctly? In the 'Displays' panel, you have some information about the RViz camera plugin. One of those is the topic that you want to use. If you click on the little arrow on the left, you get more options:

image description

You need to set the Reliability Policy from 'Reliable' to 'Best Effort' for the image to appear.

Also, why do you not simply use robot_state_publisher to publish the links of the robot? It would be a lot easier, and less likely to cause issues.

edit flag offensive delete link more

Comments

Thanks for your reply. As I wrote in the question I had set the QoS policies as required by the publisher, Best Effort and Volatile, so I'm sure it doesn't depend on that. I will try the robot_state_publisher but I always don't understand why the method I applied so far doesn't work.

Zero39 gravatar image Zero39  ( 2021-04-20 10:48:35 -0500 )edit

well, something I just noticed. The frame_name is set to robot_camera_link. However, that link doesn't exist in your sdf. The link that the plugin is in, is called link. Why do you have the camera plugin in a link, and then not use said link as the frame name?

If I were you, I would change the name of said link to robot_camera_link and use the robot_state_publisher. The error states that it drops the frame robot_camera_link, I'm not surprised if that's because that frame doesn't exist, except for in the camera plugin.

Also, you can turn on the links in Gazebo (under 'view' if I'm not mistaken. Make sure your links are set up in the way you expect them to.

EDIT: btw, if your TF's are set up correctly, you should be able to add the TF visualisation plugin to RViz and it ...(more)

Joe28965 gravatar image Joe28965  ( 2021-04-20 12:54:11 -0500 )edit

I tried to change frame_name as you suggested but I have the same results. I always have the right tree showed in Rviz but it drops all the messages. I can't use robot_state_publisherin this case because it doesn't work with sdf files, however I ran an example with another robot described through a urdf and it works.

Zero39 gravatar image Zero39  ( 2021-04-21 06:18:40 -0500 )edit

I read your original question again, but I stumbled upon an issue. What exactly is your question?

So it seems as the plugin must always be attached to the fixed frame to be properly visualized, but I'm sure it's not and I'm certainly doing something wrong that I can't figure out.

RViz has a fixed frame, that fixed frame can be set as the first option under Global Options. Yes, if you want to use the camera plugin you need to have a TF from the fixed frame that you give your camera (frame_name) and the frame you have selected in RViz under Global Options.

but I'm sure it's not and I'm certainly doing something wrong that I can't figure out.

If you you mean by 'I'm sure it's not' that you think it doesn't need a TF from ...(more)

Joe28965 gravatar image Joe28965  ( 2021-04-21 07:00:15 -0500 )edit

So if you have, for example, a 7DOF manipulator with a camera on the end effector you must create a TF from the world frame to the end effector frame in order to visualize the images?

Zero39 gravatar image Zero39  ( 2021-04-21 07:07:11 -0500 )edit

I've just realized that Rviz doesn't like dynamic transformations. If I use just static broadcasters it works well and I can watch camera stream when it's not attached to the fixed frame.

Zero39 gravatar image Zero39  ( 2021-04-21 08:44:50 -0500 )edit

Did you ever find a solution to this? I am experiencing similar behavior with a camera attached to the robot end effector.

DRO gravatar image DRO  ( 2021-08-02 23:24:35 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2021-04-19 11:46:39 -0500

Seen: 1,350 times

Last updated: Apr 20 '21