Skip to content
This repository has been archived by the owner on Aug 5, 2024. It is now read-only.

Commit

Permalink
add ZED stereovision camera
Browse files Browse the repository at this point in the history
  • Loading branch information
SwiftGust committed May 1, 2017
1 parent 25a65ad commit 7722703
Show file tree
Hide file tree
Showing 20 changed files with 3,411 additions and 18 deletions.
Binary file added gazebo_models/ZED_stereocamera/meshes/ZED.stl
Binary file not shown.
16 changes: 16 additions & 0 deletions gazebo_models/ZED_stereocamera/model.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
<?xml version="1.0"?>

<model>
<name>ZED_Stereocamera</name>
<version>1.0</version>
<sdf version="1.5">model.sdf</sdf>

<author>
<name>Seunghwan Jo</name>
<email>[email protected]</email>
</author>

<description>
StereoLabs ZED Stereovision Camera connected with ROS
</description>
</model>
89 changes: 89 additions & 0 deletions gazebo_models/ZED_stereocamera/model.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,89 @@
<?xml version="1.0" ?>
<sdf version="1.5">
<model name="ZED_stereocamera">
<link name="link">
<pose>0 0 0 0 0 0</pose>
<inertial>
<mass>0.159</mass>
<inertia>
<ixx>0.000012</ixx>
<iyy>0.000406</iyy>
<izz>0.000418</izz>
</inertia>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>0.1 0.1 0.1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<mesh>
<uri> model://ZED_stereocamera/meshes/ZED.stl</uri>
</mesh>
</geometry>
</visual>
<visual name="visual_lens_left">
<pose>0 -0.06 0 0 1.57 0</pose>
<geometry>
<cylinder>
<radius>0.007</radius>
<length>0.030</length>
</cylinder>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/WideLensMap</name>
</script>
</material>
</visual>
<visual name="visual_lens_right">
<pose>0 0.06 0 0 1.57 0</pose>
<geometry>
<cylinder>
<radius>0.007</radius>
<length>0.030</length>
</cylinder>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/WideLensMap</name>
</script>
</material>
</visual>
<sensor name="camera" type="multicamera">
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>true</visualize>
<camera name="left">
<pose>0 0 0 0 0 0</pose>
<horizontal_fov>1.91986</horizontal_fov>
<image>
<width>720</width>
<height>480</height>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
</camera>
<camera name="right">
<pose>0 -0.12 0 0 0 0</pose>
<horizontal_fov>1.91986</horizontal_fov>
<image>
<width>720</width>
<height>480</height>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
</camera>
</sensor>
</link>
</model>
</sdf>
101 changes: 101 additions & 0 deletions gazebo_models/ZED_stereocamera/zed.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,101 @@
<?xml version="1.0" ?>
<sdf version="1.6">

<model name="ZED_stereocamera">
<link name="ZED_left_camera">
<pose>0 0 0 0 1.57 0</pose>
<inertial>
<mass>0.01</mass>
<inertia>
<ixx>0.000001</ixx>
<iyy>0.000001</iyy>
<izz>0.000001</izz>
</inertia>
</inertial>
<visual>
<geometry>
<cylinder>
<radius>0.007</radius>
<length>0.031</length>
</cylinder>
</geometry>
</visual>

<sensor name="ZED_cameras" type="multicamera">
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>true</visualize>
<camera name="camera_left">
<pose>0 0 0 0 0 0 </pose>
<horizontal_fov>1.91986</horizontal_fov>
<image>
<width>720</width>
<height>480</height>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
</camera>

<camera name="camera_right">
<pose>0 -0.12 0 0 0 0 </pose>
<horizontal_fov>1.91986</horizontal_fov>
<image>
<width>720</width>
<height>480</height>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
</camera>
</sensor>
</link>

<link name="ZED_center">
<pose>0 -0.06 0 0 0 0</pose>
<inertial>
<mass>0.157</mass>
<inertia>
<ixx>0.000012</ixx>
<iyy>0.000406</iyy>
<izz>0.000418</izz>
</inertia>
</inertial>
<collision name="collision_frame">
<geometry>
<box>
<size>0.175 0.03 0.033</size>
</box>
</geometry>
<visual name="ZED_Visual">
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<uri> model://ZED_stereocamera/meshes/ZED.stl</uri>
</mesh>
</geometry>
</visual>
</link>
<link name="ZED_right_camera">
<pose>0 -0.12 0 0 0 0</pose>
<inertial>
<mass>0.01</mass>
<inertia>
<ixx>0.000001</ixx>
<iyy>0.000001</iyy>
<izz>0.000001</izz>
</inertia>
</inertial>
<visual>
<pose>0 0 0 0 1.57 0</pose>
<geometry>
<cylinder>
<radius>0.007</radius>
<length>0.031</length>
</cylinder>
</visual>
</link>
</model>
</sdf>
50 changes: 50 additions & 0 deletions gazebo_models/ZED_stereocamera/zed.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
<?xml version="1.0"?>
<robot name="zed_camera">

<link name="ZED_left_camera">
<visual>
<origin xyz="0 0 0" rpy="0 1.57 0"/>
<geometry>
<cylinder radius="0.007" length=".031"/>
</geometry>
<material name="dark_grey">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>
<link name="ZED_center">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://zed_wrapper/urdf/ZED.stl" />
</geometry>
<material name="light_grey">
<color rgba="0.8 0.8 0.8 0.8"/>
</material>
</visual>
</link>
<link name="ZED_right_camera">
<visual>
<origin xyz="0 0 0" rpy="0 1.57 0"/>
<geometry>
<cylinder radius="0.007" length=".031"/>
</geometry>
<material name="dark_grey">
<color rgba="0.1 0.1 0.1 1"/>
</material>
</visual>
</link>

<joint name="ZED_center_joint" type="fixed">
<parent link="ZED_left_camera"/>
<child link="ZED_center"/>
<origin xyz="0 -0.06 0" rpy="0 0 0" />
</joint>

<joint name="ZED_right_camera_joint" type="fixed">
<parent link="ZED_left_camera"/>
<child link="ZED_right_camera"/>
<origin xyz="0 -0.12 0" rpy="0 0 0" />
</joint>

</robot>
160 changes: 160 additions & 0 deletions gazebo_models/iris_with_sterovision/meshes/iris.dae

Large diffs are not rendered by default.

160 changes: 160 additions & 0 deletions gazebo_models/iris_with_sterovision/meshes/iris_prop_ccw.dae

Large diffs are not rendered by default.

160 changes: 160 additions & 0 deletions gazebo_models/iris_with_sterovision/meshes/iris_prop_cw.dae

Large diffs are not rendered by default.

44 changes: 44 additions & 0 deletions gazebo_models/iris_with_sterovision/model.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
<?xml version="1.0"?>

<model>
<name>Iris with Standoffs and Camera LiftDrag ArduCopter Plugins</name>
<version>1.0</version>
<sdf version="1.6">model.sdf</sdf>

<author>
<name>Fadri Furrer</name>
<email>[email protected]</email>
</author>
<author>
<name>Michael Burri</name>
</author>
<author>
<name>Mina Kamel</name>
</author>
<author>
<name>Janosch Nikolic</name>
</author>
<author>
<name>Markus Achtelik</name>
</author>

<maintainer email="[email protected]">john hsu</maintainer>


<description>
starting with iris_with_standoffs
add LiftDragPlugin
add ArduCopterPlugin
attach gimbal_small_2d model with GimbalSmall2dPlugin
</description>
<depend>
<model>
<uri>model://gimbal_small_2d</uri>
<version>1.0</version>
</model>
<model>
<uri>model://iris_with_standoffs</uri>
<version>1.0</version>
</model>
</depend>
</model>
Loading

0 comments on commit 7722703

Please sign in to comment.