Skip to content

Commit

Permalink
adding driver camera
Browse files Browse the repository at this point in the history
  • Loading branch information
braingram committed Feb 5, 2017
1 parent 30dd1bc commit 7e9f090
Showing 1 changed file with 76 additions and 0 deletions.
76 changes: 76 additions & 0 deletions src/stompy_description/urdf/stompy.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,82 @@
</visual>
</link>

<gazebo reference="camera_link">
<material>Gazebo/Red</material>
</gazebo>

<joint name="camera_joint" type="fixed">
<axis xyz="0 1 0" />
<origin xyz="1.5 0.25 0.75" rpy="0 0 0"/>
<parent link="body_link"/>
<child link="camera_link"/>
</joint>

<link name="camera_link">
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.05 0.05 0.05"/>
</geometry>
</collision>

<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.05 0.05 0.05"/>
</geometry>
<material name="red">
<color rgba="1.0 0. 0. 1.0"/>
</material>
</visual>

<inertial>
<mass value="1e-5" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
</inertial>
</link>

<gazebo reference="camera_link">
<sensor type="camera" name="camera1">
<update_rate>30.0</update_rate>
<camera name="head">
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>800</width>
<height>800</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<!-- Noise is sampled independently per pixel on each frame.
That pixel's noise value is added to each of its color
channels, which at that point lie in the range [0,1]. -->
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<updateRate>0.0</updateRate>
<cameraName>rrbot/camera1</cameraName>
<imageTopicName>image_raw</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>camera_link</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>
</gazebo>

<xacro:leg name="fl" rpy="0 0 0.9599" xyz="2.2352 0.5842 -0.1000"/>
<xacro:leg name="fr" rpy="0 0 -0.9599" xyz="2.2352 -0.5842 -0.1000"/>
<xacro:leg name="ml" rpy="0 0 1.5706" xyz="0.0 0.6858 -0.1000"/>
Expand Down

0 comments on commit 7e9f090

Please sign in to comment.