Gazebo | Ignition | Community
Ask Your Question
0

Thermal Camera Plugin not defined in SDF error

asked 2018-04-17 18:05:07 -0600

I'm trying to use the hector_gazebo_thermal_camera in a simulation for my graduation project. It returns the error:

Warning [parser.cc:778] XML Element[sensor:camera], child of element[link] not defined in SDF. Ignoring[sensor:camera]. You may have an incorrect SDF file, or an sdformat version that doesn't support this element.

I've made a simple code only with the camera and the plugin in order to validate the plugin:

This is the urdf.xacro file:

<?xml version="1.0" ?>
<robot name="robo_teste" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:property name="M_PI" value="3.141592" />
<xacro:include filename="$(find teste_thermal_cam)/urdf/model_test.gazebo.xacro" />
 <link name="my_box">
<inertial>
  <origin xyz="2 0 0" rpy = " ${-M_PI/2} 0 0"/>
  <mass value="1.0" />
  <inertia  ixx="1.0" ixy="0.0"  ixz="0.0"  iyy="100.0"  iyz="0.0"  izz="1.0" />
</inertial>
<visual>
  <origin xyz="0 0 0"/>
  <geometry>
    <box size=".1 .1 .2" />
  </geometry>
</visual>
<collision>
  <origin xyz="2 0 1"/>
  <geometry>
    <box size=".1 .1 .2" />
  </geometry>
</collision>
</link>
<gazebo reference="my_box">
<material>Gazebo/Blue</material>
</gazebo>

<link name="flir_camera">
<visual>
    <origin xyz="0 0 0" rpy="0 0 0"/>
        <geometry>
            <mesh filename="package://mybot_description/meshes/LeptonBreakoutBoardWithLepton3.stl" scale="0.001 0.001 0.001"/>
        </geometry>
        <material name="light_grey">
            <color rgba="0.8 0.8 0.8 0.8"/>
        </material>
    </visual>
</link>
<joint name="flir_camera_joint" type="fixed">
    <parent link="my_box"/>
    <child link="flir_camera"/>
<origin rpy="0 ${-M_PI/2} 0" xyz="-0.05 0.0 0.00"/>
</joint>
</robot>

and this is the .gazebo.xacro file that contains the plugin:

<?xml version="1.0" ?>
  <robot name="test_robot" xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
   xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
   xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
   xmlns:xacro="http://playerstage.sourceforge.net/gazebo/xmlschema/#xacro">

  <xacro:macro name="thermal_camera_gazebo_v0" params="name camera_name image_format image_topic_name camera_info_topic_name hfov update_rate focal_length frame_id hack_baseline image_width image_height">
<gazebo reference="my_box">
  <sensor:camera name="${name}_sensor">
    <imageSize>${image_width} ${image_height}</imageSize>
    <imageFormat>${image_format}</imageFormat>
    <hfov>${hfov}</hfov>
    <!--<nearClip>0.1</nearClip>-->
    <nearClip>0.01</nearClip>
    <farClip>100</farClip>
    <updateRate>${update_rate}</updateRate>
    <controller:gazebo_ros_thermal_camera name="${name}_controller" plugin="libgazebo_ros_thermal_depth_camera.so">
      <alwaysOn>true</alwaysOn>
      <updateRate>${update_rate}</updateRate>
      <cameraName>${camera_name}</cameraName>
      <imageTopicName>${image_topic_name}</imageTopicName>
      <cameraInfoTopicName>${camera_info_topic_name}</cameraInfoTopicName>
      <frameName>${frame_id}</frameName>
      <hackBaseline>${hack_baseline}</hackBaseline>
      <CxPrime>${(image_width+1)/2}</CxPrime>
      <Cx>${(image_width+1)/2}</Cx>
      <Cy>${(image_height+1)/2}</Cy>
      <!-- image_width / (2*tan(hfov_radian /2)) -->
      <!-- 320 for wide and 772.55 for narrow stereo camera -->
      <focalLength>${focal_length}</focalLength>
      <distortionK1>0.00000001</distortionK1>
      <distortionK2>0.00000001</distortionK2>
      <distortionK3>0.00000001</distortionK3>
      <distortionT1>0.00000001</distortionT1>
      <distortionT2>0.00000001</distortionT2>
      <interface:camera name="${name}_iface" />
    </controller:gazebo_ros_thermal_camera>
  </sensor:camera>
  <turnGravityOff>true</turnGravityOff>
  <material>Gazebo/Blue</material>
</gazebo>
</xacro:macro>
<xacro:thermal_camera_gazebo_v0 name="flir_camera" camera_name="flir_camera" image_format='R8G8B8' image_topic_name="thermal" camera_info_topic_name='detection/flir' hfov='90' update_rate='30' focal_length='320' frame_id='thermal_cam_optical_frame' hack_baseline='0' image_width ='640' image_height='480'/>

</robot>

I'm using ros Kinetic and Gazebo 7 , i've found on ... (more)

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
0

answered 2018-04-20 03:39:18 -0600

Raskkii gravatar image

Try changing:

<sensor:camera name="${name}_sensor"> to <sensor type="camera" name="${name}_sensor">

and

</sensor:camera> to </sensor>

edit flag offensive delete link more

Comments

This is one of the necessary changes, i've found one plugin that was changed to the new sdf syntax, i'll be adding it to the thread

Clebercoutof gravatar imageClebercoutof ( 2018-04-23 09:26:31 -0600 )edit
0

answered 2018-04-23 09:29:30 -0600

The plugin that is avaiable in ros wiki uses the old version of sdf syntax, since the new ones doesn't need the namespaces, only the xacro namespace, so it's necessary to modify the plugin syntax, now it's working and the xacro is:

<?xml version="1.0" ?>
<robot name="robo_teste" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="ir_camera" params="name ros_topic update_rate height width"
<gazebo reference="${name}">
<sensor type="camera" name="thermal_camera_sensor">
<update_rate>30</update_rate>
   <camera>
        <horizontal_fov>${90.0*M_PI/180.0}</horizontal_fov>
        <image>
          <format>R8G8B8</format>
          <width>${width}</width>
          <height>${height}</height>
        </image>
        <clip>
          <near>0.1</near>
          <far>300</far>
        </clip>
       </camera>
    <plugin name="thermal_camera_controller" filename="libgazebo_ros_thermal_camera.so">
      <alwaysOn>true</alwaysOn>
      <updateRate>${update_rate}</updateRate>
      <imageTopicName>/${ros_topic}/image_raw</imageTopicName>
      <cameraInfoTopicName>/${ros_topic}/camera_info</cameraInfoTopicName>
      <frameName>${name}_optical_frame</frameName>
    </plugin>
  </sensor>
</gazebo>
</xacro:macro>
</robot>
edit flag offensive delete link more

Comments

hello can i add hector_gazebo_thermal_camera on turtlebot 3 ?

rahat gravatar imagerahat ( 2020-05-17 20:08:26 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2018-04-17 18:05:07 -0600

Seen: 2,838 times

Last updated: Apr 23 '18