Skip to content

Commit

Permalink
Downward mono cam + aruco tag (#48)
Browse files Browse the repository at this point in the history
* added an arucotag to the default world

* added x500_mono_cam_down

* comment out camera_connector_arm

* center camera and increase resolution

* added aruco world

* fix name

* adjust Z position of camera
  • Loading branch information
dakejahl authored Jul 24, 2024
1 parent 312cd00 commit 4ddfc13
Show file tree
Hide file tree
Showing 7 changed files with 344 additions and 2 deletions.
Binary file added models/arucotag/arucotag.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
11 changes: 11 additions & 0 deletions models/arucotag/model.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
<?xml version="1.0"?>
<model>
<name>arucotag</name>
<version>1.0</version>
<sdf version="1.9">model.sdf</sdf>
<author>
<name>Jacob Dahl</name>
<email>[email protected]</email>
</author>
<description>Aruco tag model</description>
</model>
26 changes: 26 additions & 0 deletions models/arucotag/model.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
<?xml version="1.0" encoding="UTF-8"?>
<sdf version='1.9'>
<model name='arucotag'>
<static>true</static>
<pose>0 0 0.001 0 0 0</pose>
<link name='base'>
<visual name='base_visual'>
<geometry>
<plane>
<normal>0 0 1</normal>
<size>0.5 0.5</size>
</plane>
</geometry>
<material>
<diffuse>1 1 1 1</diffuse>
<specular>0.4 0.4 0.4 1</specular>
<pbr>
<metal>
<albedo_map>model://arucotag/arucotag.png</albedo_map>
</metal>
</pbr>
</material>
</visual>
</link>
</model>
</sdf>
34 changes: 32 additions & 2 deletions models/mono_cam/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -17,13 +17,43 @@
<izz>0.00004</izz>
</inertia>
</inertial>
<visual name="mono_cam/visual/housing">
<geometry>
<box>
<size>0.02 0.04 0.04</size>
</box>
</geometry>
</visual>
<visual name="mono_cam/visual/lens">
<pose>0.015 0 0 0 1.5707 0</pose>
<geometry>
<cylinder>
<radius>0.008</radius>
<length>0.01</length>
</cylinder>
</geometry>
</visual>
<visual name="mono_cam/visual/lens_glass">
<pose>0.014 0 0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.0079</radius>
</sphere>
</geometry>
<material>
<ambient>.4 .4 .5 .95</ambient>
<diffuse>.4 .4 .5 .95</diffuse>
<specular>1 1 1 1</specular>
<emissive>0 0 0 1</emissive>
</material>
</visual>
<sensor name="imager" type="camera">
<pose>0 0 0 0 0 0</pose>
<camera>
<horizontal_fov>1.74</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<width>1280</width>
<height>960</height>
</image>
<clip>
<near>0.1</near>
Expand Down
11 changes: 11 additions & 0 deletions models/x500_mono_cam_down/model.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
<?xml version="1.0"?>
<model>
<name>x500_mono_cam_down</name>
<version>1.0</version>
<sdf version="1.9">model.sdf</sdf>
<author>
<name>Daniel Mesham</name>
<email>[email protected]</email>
</author>
<description>An X500 with a downward-facing monocular camera.</description>
</model>
18 changes: 18 additions & 0 deletions models/x500_mono_cam_down/model.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
<?xml version="1.0" encoding="UTF-8"?>
<sdf version='1.9'>
<model name='x500_mono_cam_down'>
<self_collide>false</self_collide>
<include merge='true'>
<uri>x500</uri>
</include>
<include merge='true'>
<uri>model://mono_cam</uri>
<pose>0 0 .10 0 1.5707 0</pose>
</include>
<joint name="CameraJoint" type="fixed">
<parent>base_link</parent>
<child>mono_cam/base_link</child>
<pose relative_to="base_link">0 0 0 0 1.5707 0</pose>
</joint>
</model>
</sdf>
246 changes: 246 additions & 0 deletions worlds/aruco.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,246 @@
<?xml version="1.0" encoding="UTF-8"?>
<sdf version="1.9">
<world name="aruco">
<physics type="ode">
<max_step_size>0.004</max_step_size>
<real_time_factor>1.0</real_time_factor>
<real_time_update_rate>250</real_time_update_rate>
</physics>
<plugin name="gz::sim::systems::Physics" filename="gz-sim-physics-system"/>
<plugin name="gz::sim::systems::UserCommands" filename="gz-sim-user-commands-system"/>
<plugin name="gz::sim::systems::SceneBroadcaster" filename="gz-sim-scene-broadcaster-system"/>
<plugin name="gz::sim::systems::Contact" filename="gz-sim-contact-system"/>
<plugin name="gz::sim::systems::Imu" filename="gz-sim-imu-system"/>
<plugin name="gz::sim::systems::AirPressure" filename="gz-sim-air-pressure-system"/>
<plugin name="gz::sim::systems::ApplyLinkWrench" filename="gz-sim-apply-link-wrench-system"/>
<plugin name="gz::sim::systems::NavSat" filename="gz-sim-navsat-system"/>
<plugin name="gz::sim::systems::Sensors" filename="gz-sim-sensors-system">
<render_engine>ogre2</render_engine>
</plugin>
<gui fullscreen="false">
<!-- 3D scene -->
<plugin filename="MinimalScene" name="3D View">
<gz-gui>
<title>3D View</title>
<property type="bool" key="showTitleBar">false</property>
<property type="string" key="state">docked</property>
</gz-gui>
<engine>ogre2</engine>
<scene>scene</scene>
<ambient_light>0.4 0.4 0.4</ambient_light>
<background_color>0.8 0.8 0.8</background_color>
<camera_pose>-6 0 6 0 0.5 0</camera_pose>
<camera_clip>
<near>0.25</near>
<far>25000</far>
</camera_clip>
</plugin>
<!-- Plugins that add functionality to the scene -->
<plugin filename="EntityContextMenuPlugin" name="Entity context menu">
<gz-gui>
<property key="state" type="string">floating</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="GzSceneManager" name="Scene Manager">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="InteractiveViewControl" name="Interactive view control">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="CameraTracking" name="Camera Tracking">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="MarkerManager" name="Marker manager">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="SelectEntities" name="Select Entities">
<gz-gui>
<anchors target="Select entities">
<line own="right" target="right"/>
<line own="top" target="top"/>
</anchors>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="VisualizationCapabilities" name="Visualization Capabilities">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="Spawn" name="Spawn Entities">
<gz-gui>
<anchors target="Select entities">
<line own="right" target="right"/>
<line own="top" target="top"/>
</anchors>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin name="World control" filename="WorldControl">
<gz-gui>
<title>World control</title>
<property type="bool" key="showTitleBar">0</property>
<property type="bool" key="resizable">0</property>
<property type="double" key="height">72</property>
<property type="double" key="width">121</property>
<property type="double" key="z">1</property>
<property type="string" key="state">floating</property>
<anchors target="3D View">
<line own="left" target="left"/>
<line own="bottom" target="bottom"/>
</anchors>
</gz-gui>
<play_pause>1</play_pause>
<step>1</step>
<start_paused>1</start_paused>
</plugin>
<plugin name="World stats" filename="WorldStats">
<gz-gui>
<title>World stats</title>
<property type="bool" key="showTitleBar">0</property>
<property type="bool" key="resizable">0</property>
<property type="double" key="height">110</property>
<property type="double" key="width">290</property>
<property type="double" key="z">1</property>
<property type="string" key="state">floating</property>
<anchors target="3D View">
<line own="right" target="right"/>
<line own="bottom" target="bottom"/>
</anchors>
</gz-gui>
<sim_time>1</sim_time>
<real_time>1</real_time>
<real_time_factor>1</real_time_factor>
<iterations>1</iterations>
</plugin>
<plugin name="Entity tree" filename="EntityTree"/>
</gui>
<gravity>0 0 -9.8</gravity>
<magnetic_field>6e-06 2.3e-05 -4.2e-05</magnetic_field>
<atmosphere type="adiabatic"/>
<scene>
<grid>false</grid>
<ambient>0.4 0.4 0.4 1</ambient>
<background>0.7 0.7 0.7 1</background>
<shadows>true</shadows>
</scene>
<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>1 1</size>
</plane>
</geometry>
<surface>
<friction>
<ode/>
</friction>
<bounce/>
<contact/>
</surface>
</collision>
<visual name="visual">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
<pose>0 0 0 0 -0 0</pose>
<inertial>
<pose>0 0 0 0 -0 0</pose>
<mass>1</mass>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
</inertial>
<enable_wind>false</enable_wind>
</link>
<pose>0 0 0 0 -0 0</pose>
<self_collide>false</self_collide>
</model>
<light name="sunUTC" type="directional">
<pose>0 0 500 0 -0 0</pose>
<cast_shadows>true</cast_shadows>
<intensity>1</intensity>
<direction>0.001 0.625 -0.78</direction>
<diffuse>0.904 0.904 0.904 1</diffuse>
<specular>0.271 0.271 0.271 1</specular>
<attenuation>
<range>2000</range>
<linear>0</linear>
<constant>1</constant>
<quadratic>0</quadratic>
</attenuation>
<spot>
<inner_angle>0</inner_angle>
<outer_angle>0</outer_angle>
<falloff>0</falloff>
</spot>
</light>
<spherical_coordinates>
<surface_model>EARTH_WGS84</surface_model>
<world_frame_orientation>ENU</world_frame_orientation>
<latitude_deg>47.397971057728974</latitude_deg>
<longitude_deg> 8.546163739800146</longitude_deg>
<elevation>0</elevation>
</spherical_coordinates>

<include>
<uri>model://arucotag</uri>
</include>
</world>
</sdf>

0 comments on commit 4ddfc13

Please sign in to comment.