Skip to content

Commit

Permalink
Add a wide angle camera with lens flare plugin (#7)
Browse files Browse the repository at this point in the history

---------

Signed-off-by: Ian Chen <[email protected]>
  • Loading branch information
iche033 authored Sep 29, 2023
1 parent 4ddfde6 commit e41f701
Showing 1 changed file with 31 additions and 7 deletions.
38 changes: 31 additions & 7 deletions harmonic_demo/harmonic.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -500,35 +500,59 @@
<uri>CartPole</uri>
</include>

<model name="camera">
<!-- wide-angle camera model with lens flare plugin -->
<model name="wide_angle_camera_lensflare">
<static>true</static>
<pose>-9 -7.5 15 0.0, 0.4, 1.38</pose>
<pose>1.08 4.54 8.56 0.0 0.0 1.57</pose>
<link name="link">
<pose>0.05 0.05 0.05 0 0 0</pose>
<visual name="visual">
<geometry>
<box>
<size>0.1 0.1 0.1</size>
</box>
</geometry>
</visual>
<sensor name="camera" type="camera">
<visual name="center">
<pose>0.02 0 0 0.0 1.57 0</pose>
<geometry>
<sphere>
<radius>0.04</radius>
</sphere>
</geometry>
<material>
<diffuse>0.2 0.2 0.2</diffuse>
</material>
</visual>
<sensor name="wide_angle_camera" type="wideanglecamera">
<camera>
<horizontal_fov>1.57</horizontal_fov>
<horizontal_fov>3.14159</horizontal_fov>
<image>
<width>320</width>
<height>240</height>
<width>640</width>
<height>480</height>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
<lens>
<type>equidistant</type>
<scale_to_hfov>true</scale_to_hfov>
<cutoff_angle>1.5707</cutoff_angle>
<env_texture_size>512</env_texture_size>
</lens>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>true</visualize>
<topic>wide_angle_camera</topic>
<plugin
filename="gz-sim-lens-flare-system"
name="gz::sim::systems::LensFlare">
<light_name>sun</light_name>
</plugin>
</sensor>
</link>
</model>

</world>
</sdf>

0 comments on commit e41f701

Please sign in to comment.