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

ROS Topics not being published with Gazebo

asked 2020-11-15 18:48:44 -0500

iamrandom gravatar image

updated 2022-05-28 16:45:25 -0500

lucasw gravatar image

I have the following camera sensor added in a .world file:

<model name='camera'>
  <link name='link'>
    <inertial>
      <mass>0.1</mass>
      <inertia>
        <ixx>0.000166667</ixx>
        <iyy>0.000166667</iyy>
        <izz>0.000166667</izz>
        <ixy>0</ixy>
        <ixz>0</ixz>
        <iyz>0</iyz>
      </inertia>
      <pose frame=''>0 0 0 0 -0 0</pose>
    </inertial>
    <sensor name='camera' type='camera'>
      <camera name='__default__'>
        <horizontal_fov>1.047</horizontal_fov>
        <image>
          <width>320</width>
          <height>240</height>
        </image>
        <clip>
          <near>0.1</near>
          <far>100</far>
        </clip>
      </camera>
      <always_on>1</always_on>
      <update_rate>30</update_rate>
      <visualize>1</visualize>
    </sensor>
    <self_collide>0</self_collide>
    <enable_wind>0</enable_wind>
    <kinematic>0</kinematic>
    <pose frame=''>0 0 0 0 -0 0</pose>
    <visual name='visual'>
      <geometry>
        <box>
          <size>0.1 0.1 0.1</size>
        </box>
      </geometry>
      <material>
        <shader type='pixel'/>
      </material>
      <pose frame=''>0 0 0 0 -0 0</pose>
      <transparency>0</transparency>
      <cast_shadows>1</cast_shadows>
    </visual>
    <collision name='collision'>
      <laser_retro>0</laser_retro>
      <max_contacts>10</max_contacts>
      <pose frame=''>0 0 0 0 -0 0</pose>
      <geometry>
        <box>
          <size>0.1 0.1 0.1</size>
        </box>
      </geometry>
      <surface>
        <friction>
          <ode>
            <mu>1</mu>
            <mu2>1</mu2>
            <fdir1>0 0 0</fdir1>
            <slip1>0</slip1>
            <slip2>0</slip2>
          </ode>
          <torsional>
            <coefficient>1</coefficient>
            <patch_radius>0</patch_radius>
            <surface_radius>0</surface_radius>
            <use_patch_radius>1</use_patch_radius>
            <ode>
              <slip>0</slip>
            </ode>
          </torsional>
        </friction>
        <bounce>
          <restitution_coefficient>0</restitution_coefficient>
          <threshold>1e+06</threshold>
        </bounce>
        <contact>
          <collide_without_contact>0</collide_without_contact>
          <collide_without_contact_bitmask>1</collide_without_contact_bitmask>
          <collide_bitmask>1</collide_bitmask>
          <ode>
            <soft_cfm>0</soft_cfm>
            <soft_erp>0.2</soft_erp>
            <kp>1e+13</kp>
            <kd>1</kd>
            <max_vel>0.01</max_vel>
            <min_depth>0</min_depth>
          </ode>
          <bullet>
            <split_impulse>1</split_impulse>
            <split_impulse_penetration_threshold>-0.01</split_impulse_penetration_threshold>
            <soft_cfm>0</soft_cfm>
            <soft_erp>0.2</soft_erp>
            <kp>1e+13</kp>
            <kd>1</kd>
          </bullet>
        </contact>
      </surface>
    </collision>
  </link>
  <static>0</static>
  <allow_auto_disable>1</allow_auto_disable>
  <plugin name='stereo_camera_controller' filename='libgazebo_ros_multicamera.so'>
    <alwaysOn>1</alwaysOn>
    <updateRate>0.0</updateRate>
    <cameraName>test/camera</cameraName>
    <imageTopicName>image_raw</imageTopicName>
    <cameraInfoTopicName>camera_info</cameraInfoTopicName>
    <frameName>left_camera_optical_frame</frameName>
    <hackBaseline>0.07</hackBaseline>
    <distortionK1>0.0</distortionK1>
    <distortionK2>0.0</distortionK2>
    <distortionK3>0.0</distortionK3>
    <distortionT1>0.0</distortionT1>
    <distortionT2>0.0</distortionT2>
  </plugin>
  <pose frame=''>-22.3817 16.9364 0.05 0 -0 0</pose>
</model>

The simulation launches with the model, but when I look for the topic for the camera does not show up. Any suggestions?

edit retag flag offensive close merge delete

Comments

1

I don't have much experience with cameras in Gazebo, but it seems that you have a camera sensor defined but are trying to use the multicamera plugin. Also, judging by the Gazebo tutorial, the plugin element should be nested inside the sensor element.

tryan gravatar image tryan  ( 2020-11-16 15:41:38 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2020-12-18 13:31:00 -0500

gerkey gravatar image

@tryan's two points are right: for a single camera you should use the camera_controller plugin, and you should put the plugin block inside the sensor block. Below is a complete world file with those two change that works correctly. Save it as foo.world and then run it as roslaunch gazebo_ros empty_world.launch world_name:=pwd/foo.world. After simulation is up, rostopic list includes the desired camera topics:

/test/camera/camera_info
/test/camera/image_raw
/test/camera/parameter_descriptions
/test/camera/parameter_updates

foo.world:

<?xml version="1.0" ?>
<sdf version="1.5">
  <world name="default">
    <!-- A global light source -->
    <include>
      <uri>model://sun</uri>
    </include>
    <!-- A ground plane -->
    <include>
      <uri>model://ground_plane</uri>
    </include>
    <model name='camera'>
      <link name='link'>
        <inertial>
          <mass>0.1</mass>
          <inertia>
            <ixx>0.000166667</ixx>
            <iyy>0.000166667</iyy>
            <izz>0.000166667</izz>
            <ixy>0</ixy>
            <ixz>0</ixz>
            <iyz>0</iyz>
          </inertia>
          <pose frame=''>0 0 0 0 -0 0</pose>
        </inertial>
        <sensor name='camera' type='camera'>
          <camera name='__default__'>
            <horizontal_fov>1.047</horizontal_fov>
            <image>
              <width>320</width>
              <height>240</height>
            </image>
            <clip>
              <near>0.1</near>
              <far>100</far>
            </clip>
          </camera>
          <always_on>1</always_on>
          <update_rate>30</update_rate>
          <visualize>1</visualize>
        <plugin name='camera_controller' filename='libgazebo_ros_camera.so'>
          <alwaysOn>1</alwaysOn>
          <updateRate>0.0</updateRate>
          <cameraName>test/camera</cameraName>
          <imageTopicName>image_raw</imageTopicName>
          <cameraInfoTopicName>camera_info</cameraInfoTopicName>
          <frameName>left_camera_optical_frame</frameName>
          <hackBaseline>0.07</hackBaseline>
          <distortionK1>0.0</distortionK1>
          <distortionK2>0.0</distortionK2>
          <distortionK3>0.0</distortionK3>
          <distortionT1>0.0</distortionT1>
          <distortionT2>0.0</distortionT2>
        </plugin>
        </sensor>
        <self_collide>0</self_collide>
        <enable_wind>0</enable_wind>
        <kinematic>0</kinematic>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <visual name='visual'>
          <geometry>
            <box>
              <size>0.1 0.1 0.1</size>
            </box>
          </geometry>
          <material>
            <shader type='pixel'/>
          </material>
          <pose frame=''>0 0 0 0 -0 0</pose>
          <transparency>0</transparency>
          <cast_shadows>1</cast_shadows>
        </visual>
        <collision name='collision'>
          <laser_retro>0</laser_retro>
          <max_contacts>10</max_contacts>
          <pose frame=''>0 0 0 0 -0 0</pose>
          <geometry>
            <box>
              <size>0.1 0.1 0.1</size>
            </box>
          </geometry>
          <surface>
            <friction>
              <ode>
                <mu>1</mu>
                <mu2>1</mu2>
                <fdir1>0 0 0</fdir1>
                <slip1>0</slip1>
                <slip2>0</slip2>
              </ode>
              <torsional>
                <coefficient>1</coefficient>
                <patch_radius>0</patch_radius>
                <surface_radius>0</surface_radius>
                <use_patch_radius>1</use_patch_radius>
                <ode>
                  <slip>0</slip>
                </ode>
              </torsional>
            </friction>
            <bounce>
              <restitution_coefficient>0</restitution_coefficient>
              <threshold>1e+06</threshold>
            </bounce>
            <contact>
              <collide_without_contact>0</collide_without_contact>
              <collide_without_contact_bitmask>1</collide_without_contact_bitmask>
              <collide_bitmask>1</collide_bitmask>
              <ode>
                <soft_cfm>0</soft_cfm>
                <soft_erp>0.2</soft_erp>
                <kp>1e+13</kp>
                <kd>1</kd>
                <max_vel>0.01</max_vel>
                <min_depth>0</min_depth>
              </ode>
              <bullet>
                <split_impulse>1</split_impulse>
                <split_impulse_penetration_threshold>-0.01</split_impulse_penetration_threshold>
                <soft_cfm>0</soft_cfm>
                <soft_erp>0.2</soft_erp>
                <kp>1e+13</kp>
                <kd>1</kd>
              </bullet>
            </contact>
          </surface>
        </collision>
      </link>
      <static>0</static>
      <allow_auto_disable>1</allow_auto_disable>
      <pose frame=''>-22.3817 16.9364 0.05 0 -0 0</pose>
    </model>
  </world>
</sdf>
edit flag offensive delete link more

Comments

1

This worked! Thanks to @tryan as well for the comment.

iamrandom gravatar image iamrandom  ( 2020-12-30 16:42:25 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2020-11-15 18:48:44 -0500

Seen: 1,148 times

Last updated: Dec 18 '20