104 lines
3.2 KiB
XML
104 lines
3.2 KiB
XML
<?xml version="1.0"?>
|
|
<sdf version="1.6">
|
|
<model name="realsense_d435">
|
|
<link name="link">
|
|
<inertial>
|
|
<mass>0.0615752</mass>
|
|
<inertia>
|
|
<ixx>9.108e-05</ixx>
|
|
<ixy>0</ixy>
|
|
<ixz>0</ixz>
|
|
<iyy>2.51e-06</iyy>
|
|
<iyz>0</iyz>
|
|
<izz>8.931e-05</izz>
|
|
</inertia>
|
|
<pose frame=''>0 0 0 0 -0 0</pose>
|
|
</inertial>
|
|
<collision name="collision">
|
|
<geometry>
|
|
<mesh>
|
|
<uri>model://RealSense_D435/meshes/realsense.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
</collision>
|
|
<visual name= "visual">
|
|
<geometry>
|
|
<mesh>
|
|
<uri>model://RealSense_D435/meshes/realsense.dae</uri>
|
|
<submesh>
|
|
<name>RealSense</name>
|
|
<center>false</center>
|
|
</submesh>
|
|
</mesh>
|
|
</geometry>
|
|
<material>
|
|
<diffuse>1.0 1.0 1.0</diffuse>
|
|
<specular>1.0 1.0 1.0</specular>
|
|
<pbr>
|
|
<metal>
|
|
<albedo_map>model://RealSense_D435/materials/textures/RealSense_Albedo.png</albedo_map>
|
|
<normal_map>model://RealSense_D435/materials/textures/RealSense_Normal.png</normal_map>
|
|
<metalness_map>model://RealSense_D435/materials/textures/RealSense_Metalness.png</metalness_map>
|
|
<roughness_map>model://RealSense_D435/materials/textures/RealSense_Roughness.png</roughness_map>
|
|
</metal>
|
|
</pbr>
|
|
<!-- fallback to script if no PBR support-->
|
|
<script>
|
|
<uri>model://RealSense_D435/materials/scripts/</uri>
|
|
<uri>model://RealSense_D435/materials/textures/</uri>
|
|
<name>UrbanTile/RealSense_Diffuse</name>
|
|
</script>
|
|
</material>
|
|
</visual>
|
|
|
|
<sensor name="realsense_d435" type="rgbd_camera">
|
|
<update_rate>60</update_rate>
|
|
<camera name="camera">
|
|
<horizontal_fov>1.0472</horizontal_fov>
|
|
<lens>
|
|
<intrinsics>
|
|
<!-- fx = fy = width / ( 2 * tan (hfov / 2 ) ) -->
|
|
<fx>554.25469</fx>
|
|
<fy>554.25469</fy>
|
|
<!-- cx = ( width + 1 ) / 2 -->
|
|
<cx>320.5</cx>
|
|
<!-- cy = ( height + 1 ) / 2 -->
|
|
<cy>240.5</cy>
|
|
<s>0</s>
|
|
</intrinsics>
|
|
</lens>
|
|
<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>
|
|
<image>
|
|
<width>640</width>
|
|
<height>480</height>
|
|
<format>R8G8B8</format>
|
|
</image>
|
|
<clip>
|
|
<near>0.01</near>
|
|
<far>300</far>
|
|
</clip>
|
|
<depth_camera>
|
|
<clip>
|
|
<near>0.1</near>
|
|
<far>10</far>
|
|
</clip>
|
|
</depth_camera>
|
|
<noise>
|
|
<type>gaussian</type>
|
|
<mean>0</mean>
|
|
<stddev>0.007</stddev>
|
|
</noise>
|
|
</camera>
|
|
</sensor>
|
|
|
|
</link>
|
|
</model>
|
|
</sdf>
|