Newer
Older
orange2022 / src / junk / tsukuba2022 / urdf / sensors / camera.urdf.xacro
@koki koki on 20 Sep 2022 2 KB update
<?xml version="1.0"?>
<robot name="sensor_camera" xmlns:xacro="http://ros.org/wiki/xacro"
                            xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
                            xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface">

  <xacro:property name="camera" value="0.1"/> 

  <xacro:macro name="sensor_camera" params="name parent *origin">
    <joint name="${name}_joint" type="fixed">
      <xacro:insert_block name="origin"/>
      <axis xyz="0 1 0"/>
      <parent link="${parent}"/>
      <child link="${name}_link"/>
    </joint>
    
    <link name="${name}_link">
      <visual>
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <geometry>
            <sphere radius="0.015"/>
        </geometry>
      </visual>

      <collision>
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <geometry>
            <sphere radius="0.015"/>
        </geometry>
      </collision>
    </link>
   
  <gazebo reference="${name}_link">
    <sensor type="wideanglecamera" name="cv_camera">
      <update_rate>30.0</update_rate>
      <camera>
        <pose>0 0 0 0 ${PI/2} 0</pose>
        <horizontal_fov>3.1415</horizontal_fov>
        <image>
          <format>R8G8B8</format>
          <width>800</width>
          <height>800</height>
        </image>
        <clip>
          <near>0.01</near>
          <far>100</far>
        </clip>
        <lens>
          <type>stereographic</type>
          <scale_to_hfov>1</scale_to_hfov>
          <cutoff_angle>1.5707</cutoff_angle>
          <env_texture_size>512</env_texture_size>
        </lens>
      </camera>
      
      <plugin name="camera_controller" filename="libgazebo_ros_camera.so">
        <alwaysOn>true</alwaysOn>
        <updateRate>0.0</updateRate>
        <cameraName>cv_camera</cameraName>
        <imageTopicName>image_raw</imageTopicName>
        <cameraInfoTopicName>camera_info</cameraInfoTopicName>
        <frameName>camera_link</frameName>
        <hackBaseline>0.0</hackBaseline>
        <distortionK1>0.0</distortionK1>
        <distortionK2>0.0</distortionK2>
        <distortionK3>0.0</distortionK3>
        <distortionT1>0.0</distortionT1>
        <distortionT2>0.0</distortionT2>
      </plugin>
    </sensor>
    <material>Gazebo/DarkGray</material>
  </gazebo>
  </xacro:macro>

</robot>