154 lines
4.1 KiB
XML
154 lines
4.1 KiB
XML
<?xml version='1.0'?>
|
|
<sdf version='1.9'>
|
|
<model name='gimbal_small_1d'>
|
|
<pose>0 0 0.18 0 0 0</pose>
|
|
<link name='base_link'>
|
|
<inertial>
|
|
<mass>0.2</mass>
|
|
<inertia>
|
|
<ixx>0.0001</ixx>
|
|
<ixy>0</ixy>
|
|
<ixz>0</ixz>
|
|
<iyy>0.0001</iyy>
|
|
<iyz>0</iyz>
|
|
<izz>0.0001</izz>
|
|
</inertia>
|
|
</inertial>
|
|
<visual name='base_main_viz'>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>0.001 0.001 0.001</scale>
|
|
<uri>model://gimbal_small_1d/meshes/base_main.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
<material>
|
|
<ambient>0.1 0.1 0.1</ambient>
|
|
<diffuse>0.1 0.1 0.1</diffuse>
|
|
<specular>0.01 0.01 0.01 1.0</specular>
|
|
</material>
|
|
</visual>
|
|
<visual name='base_arm_viz'>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>0.001 0.001 0.001</scale>
|
|
<uri>model://gimbal_small_1d/meshes/base_arm.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
<material>
|
|
<ambient>0.1 0.1 0.1</ambient>
|
|
<diffuse>0.1 0.1 0.1</diffuse>
|
|
<specular>0.01 0.01 0.01 1.0</specular>
|
|
</material>
|
|
</visual>
|
|
<collision name='base_col'>
|
|
<pose>0.01 0.075 -0.025 0 0 0</pose>
|
|
<geometry>
|
|
<box>
|
|
<size>0.1 0.05 0.15</size>
|
|
</box>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<link name='tilt_link'>
|
|
<inertial>
|
|
<mass>0.01</mass>
|
|
<inertia>
|
|
<ixx>0.00001</ixx>
|
|
<ixy>0</ixy>
|
|
<ixz>0</ixz>
|
|
<iyy>0.00001</iyy>
|
|
<iyz>0</iyz>
|
|
<izz>0.00001</izz>
|
|
</inertia>
|
|
</inertial>
|
|
<visual name='tilt_viz'>
|
|
<pose>0 0 -0.005 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>0.001 0.001 0.001</scale>
|
|
<uri>model://gimbal_small_1d/meshes/tilt.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
<material>
|
|
<ambient>0.4 0.4 0.4</ambient>
|
|
<diffuse>0.4 0.4 0.4</diffuse>
|
|
<specular>0.1 0.1 0.1 1.0</specular>
|
|
</material>
|
|
</visual>
|
|
<collision name='tilt_col'>
|
|
<pose>0 0 -0.005 0 0 0</pose>
|
|
<geometry>
|
|
<mesh>
|
|
<scale>0.001 0.001 0.001</scale>
|
|
<uri>model://gimbal_small_1d/meshes/tilt.dae</uri>
|
|
</mesh>
|
|
</geometry>
|
|
</collision>
|
|
<visual name='camera_viz'>
|
|
<pose>0 0 0.02 0 0 0</pose>
|
|
<geometry>
|
|
<cylinder>
|
|
<radius>0.025</radius>
|
|
<length>0.050</length>
|
|
</cylinder>
|
|
</geometry>
|
|
<material>
|
|
<ambient>0.4 0.4 0.4</ambient>
|
|
<diffuse>0.4 0.4 0.4</diffuse>
|
|
<specular>0.1 0.1 0.1 1.0</specular>
|
|
</material>
|
|
</visual>
|
|
<collision name='camera_col'>
|
|
<pose>0 0 0.02 0 0 0</pose>
|
|
<geometry>
|
|
<cylinder>
|
|
<radius>0.025</radius>
|
|
<length>0.050</length>
|
|
</cylinder>
|
|
</geometry>
|
|
</collision>
|
|
<sensor name="camera" type="camera">
|
|
<pose degrees="true">0 0 0 -90 -90 0</pose>
|
|
<camera>
|
|
<horizontal_fov>2.0</horizontal_fov>
|
|
<image>
|
|
<width>640</width>
|
|
<height>480</height>
|
|
</image>
|
|
<clip>
|
|
<near>0.05</near>
|
|
<far>15000</far>
|
|
</clip>
|
|
</camera>
|
|
<always_on>1</always_on>
|
|
<update_rate>10</update_rate>
|
|
<visualize>1</visualize>
|
|
|
|
<plugin name="GstCameraPlugin"
|
|
filename="GstCameraPlugin">
|
|
<udp_host>127.0.0.1</udp_host>
|
|
<udp_port>5600</udp_port>
|
|
<use_basic_pipeline>true</use_basic_pipeline>
|
|
<use_cuda>false</use_cuda>
|
|
</plugin>
|
|
|
|
</sensor>
|
|
</link>
|
|
<joint name='tilt_joint' type='revolute'>
|
|
<parent>base_link</parent>
|
|
<child>tilt_link</child>
|
|
<axis>
|
|
<xyz>1 0 0</xyz>
|
|
<dynamics>
|
|
<damping>0.01</damping>
|
|
</dynamics>
|
|
<limit>
|
|
<lower>-3.1415926</lower>
|
|
<upper>3.1415926</upper>
|
|
</limit>
|
|
</axis>
|
|
<pose>0 0 0.02 0 0 0</pose>
|
|
</joint>
|
|
</model>
|
|
</sdf>
|