Created
October 2, 2014 22:15
-
-
Save jbohren/eb9fc0694ef53282ccc9 to your computer and use it in GitHub Desktop.
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
<sdf version='1.4'> | |
<model name='stereo_cam'> | |
<link name='bumblebee_mount_link'> | |
<pose>0 0 1 1.5707 -0 0</pose> | |
<inertial> | |
<pose>0 0 0 0 -0 0</pose> | |
<mass>0.342001</mass> | |
<inertia> | |
<ixx>0.000101969</ixx> | |
<ixy>0</ixy> | |
<ixz>0</ixz> | |
<iyy>0.000767529</iyy> | |
<iyz>0</iyz> | |
<izz>0.000740433</izz> | |
</inertia> | |
</inertial> | |
<collision name='bumblebee_mount_link_collision'> | |
<pose>0 0 0 0 -0 0</pose> | |
<geometry> | |
<mesh> | |
<scale>1 1 1</scale> | |
<uri>model://lcsr_camera_models/cameras/bumblebee/bumblebee2.dae</uri> | |
</mesh> | |
</geometry> | |
</collision> | |
<visual name='bumblebee_mount_link_visual'> | |
<pose>0 0 0 0 -0 0</pose> | |
<geometry> | |
<mesh> | |
<scale>1 1 1</scale> | |
<uri>model://lcsr_camera_models/cameras/bumblebee/bumblebee2.dae</uri> | |
</mesh> | |
</geometry> | |
</visual> | |
<gravity>1</gravity> | |
<velocity_decay> | |
<linear>0</linear> | |
<angular>0</angular> | |
</velocity_decay> | |
<self_collide>0</self_collide> | |
<sensor name='stereo_camera' type='multicamera'> | |
<update_rate>48</update_rate> | |
<camera name='left'> | |
<pose>0.06 0 0 -5.76279e-13 1.5707 1.5707</pose> | |
<horizontal_fov>1.15192</horizontal_fov> | |
<image> | |
<width>640</width> | |
<height>480</height> | |
<format>R8G8B8</format> | |
</image> | |
<clip> | |
<near>0.05</near> | |
<far>300</far> | |
</clip> | |
<noise> | |
<type>gaussian</type> | |
<mean>0</mean> | |
<stddev>0.007</stddev> | |
</noise> | |
</camera> | |
<camera name='right'> | |
<pose>-0.06 0 0 -5.76279e-13 1.5707 1.5707</pose> | |
<horizontal_fov>1.15192</horizontal_fov> | |
<image> | |
<width>640</width> | |
<height>480</height> | |
<format>R8G8B8</format> | |
</image> | |
<clip> | |
<near>0.05</near> | |
<far>300</far> | |
</clip> | |
<noise> | |
<type>gaussian</type> | |
<mean>0</mean> | |
<stddev>0.007</stddev> | |
</noise> | |
</camera> | |
<plugin name='stereo_camera_controller' filename='libgazebo_ros_multicamera.so'> | |
<alwaysOn>true</alwaysOn> | |
<cameraName>bumblebee/camera</cameraName> | |
<imageTopicName>image_raw</imageTopicName> | |
<cameraInfoTopicName>camera_info</cameraInfoTopicName> | |
<frameName>bumblebee_optical_frame</frameName> | |
<hackBaseline>0.12</hackBaseline> | |
<distortionK1>0.0</distortionK1> | |
<distortionK2>0.0</distortionK2> | |
<distortionK3>0.0</distortionK3> | |
<distortionT1>0.0</distortionT1> | |
<distortionT2>0.0</distortionT2> | |
</plugin> | |
<pose>0 0 0 0 -0 0</pose> | |
</sensor> | |
</link> | |
<joint name='bumblebee2_mount_joint' type='revolute'> | |
<child>bumblebee_mount_link</child> | |
<parent>world</parent> | |
<axis> | |
<limit> | |
<lower>0</lower> | |
<upper>0</upper> | |
</limit> | |
<dynamics> | |
<damping>0</damping> | |
</dynamics> | |
<xyz>0 0 1</xyz> | |
</axis> | |
</joint> | |
</model> | |
</sdf> |
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
<?xml version="1.0" ?> | |
<!-- =================================================================================== --> | |
<!-- | This document was autogenerated by xacro from test.urdf.xacro | --> | |
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | --> | |
<!-- =================================================================================== --> | |
<robot name="stereo_cam" xmlns:xacro="http://www.ros.org/wiki/xacro"> | |
<link name="world"/> | |
<joint name="bumblebee2_mount_joint" type="fixed"> | |
<parent link="world"/> | |
<child link="bumblebee_mount_link"/> | |
<origin rpy="1.5707 0 0" xyz="0 0 1.0"/> | |
</joint> | |
<link name="bumblebee_mount_link"> | |
<visual> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://lcsr_camera_models/cameras/bumblebee/bumblebee2.dae"/> | |
</geometry> | |
</visual> | |
<collision> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
<geometry> | |
<mesh filename="package://lcsr_camera_models/cameras/bumblebee/bumblebee2.dae"/> | |
</geometry> | |
</collision> | |
<inertial> | |
<mass value="0.342"/> | |
<inertia ixx="0.00010096866" ixy="0" ixz="0" iyy="0.00076652916" iyz="0" izz="0.0007394325"/> | |
</inertial> | |
</link> | |
<joint name="bumblebee_optical_joint" type="fixed"> | |
<parent link="bumblebee_mount_link"/> | |
<child link="bumblebee_optical_frame"/> | |
<origin rpy="0 0 0" xyz="0 0 0"/> | |
</joint> | |
<link name="bumblebee_optical_frame"> | |
<inertial> | |
<mass value="1E-6"/> | |
<inertia ixx="1E-6" ixy="0" ixz="0" iyy="1E-6" iyz="0" izz="1E-6"/> | |
</inertial> | |
</link> | |
<gazebo reference="bumblebee_optical_frame"> | |
<sensor name="stereo_camera" type="multicamera"> | |
<update_rate>48</update_rate> | |
<camera name="left"> | |
<pose>0.06 0 0 0 1.5707 1.5707</pose> | |
<horizontal_fov>1.15191730632</horizontal_fov> | |
<image> | |
<width>640</width> | |
<height>480</height> | |
<format>R8G8B8</format> | |
</image> | |
<clip> | |
<near>0.05</near> | |
<far>300</far> | |
</clip> | |
<noise> | |
<type>gaussian</type> | |
<mean>0.0</mean> | |
<stddev>0.007</stddev> | |
</noise> | |
</camera> | |
<camera name="right"> | |
<pose>-0.06 0 0 0 1.5707 1.5707</pose> | |
<horizontal_fov>1.15191730632</horizontal_fov> | |
<image> | |
<width>640</width> | |
<height>480</height> | |
<format>R8G8B8</format> | |
</image> | |
<clip> | |
<near>0.05</near> | |
<far>300</far> | |
</clip> | |
<noise> | |
<type>gaussian</type> | |
<mean>0.0</mean> | |
<stddev>0.007</stddev> | |
</noise> | |
</camera> | |
<plugin filename="libgazebo_ros_multicamera.so" name="stereo_camera_controller"> | |
<alwaysOn>true</alwaysOn> | |
<cameraName>bumblebee/camera</cameraName> | |
<imageTopicName>image_raw</imageTopicName> | |
<cameraInfoTopicName>camera_info</cameraInfoTopicName> | |
<frameName>bumblebee_optical_frame</frameName> | |
<hackBaseline>0.12</hackBaseline> | |
<!--<rightFrameName>right_camera_optical_frame</rightFrameName>--> | |
<!-- NOTE: Distortion is currently unused --> | |
<distortionK1>0.0</distortionK1> | |
<distortionK2>0.0</distortionK2> | |
<distortionK3>0.0</distortionK3> | |
<distortionT1>0.0</distortionT1> | |
<distortionT2>0.0</distortionT2> | |
</plugin> | |
</sensor> | |
</gazebo> | |
</robot> |
Sign up for free
to join this conversation on GitHub.
Already have an account?
Sign in to comment