Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add support for sky #445

Merged
merged 7 commits into from
Dec 18, 2020
Merged
Show file tree
Hide file tree
Changes from 6 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
305 changes: 305 additions & 0 deletions examples/worlds/sky.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,305 @@
<?xml version="1.0" ?>
<!--

Showcase a world with sky enabled.
Currently only supported using ogre2 rendering engine plugin.

-->

<sdf version="1.7">

<world name="sky">

<gui>
<!-- 3D scene -->
<plugin filename="GzScene3D" name="3D View">
<ignition-gui>
<title>3D View</title>
<property type="bool" key="showTitleBar">false</property>
<property type="string" key="state">docked</property>
</ignition-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>
<sky></sky>
<camera_pose>6 0 1.0 0 0.0 3.14</camera_pose>
</plugin>

<!-- Play / pause / step -->
<plugin filename="WorldControl" name="World control">
<ignition-gui>
<title>World control</title>
<property type="bool" key="showTitleBar">false</property>
<property type="bool" key="resizable">false</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>
</ignition-gui>

<play_pause>true</play_pause>
<step>true</step>
<start_paused>true</start_paused>

</plugin>

<!-- Time / RTF -->
<plugin filename="WorldStats" name="World stats">
<ignition-gui>
<title>World stats</title>
<property type="bool" key="showTitleBar">false</property>
<property type="bool" key="resizable">false</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>
</ignition-gui>

<sim_time>true</sim_time>
<real_time>true</real_time>
<real_time_factor>true</real_time_factor>
<iterations>true</iterations>

</plugin>

<plugin filename="ImageDisplay" name="Image Display">
<ignition-gui>
<title>RGB camera</title>
<property type="double" key="width">350</property>
<property type="double" key="height">315</property>
</ignition-gui>
<topic>camera</topic>
</plugin>

</gui>


<physics name="1ms" type="ignored">
<max_step_size>0.001</max_step_size>
<real_time_factor>1.0</real_time_factor>
</physics>
<plugin
filename="ignition-gazebo-physics-system"
name="ignition::gazebo::systems::Physics">
</plugin>
<plugin
filename="ignition-gazebo-sensors-system"
name="ignition::gazebo::systems::Sensors">
<render_engine>ogre2</render_engine>
</plugin>
<plugin
filename="ignition-gazebo-user-commands-system"
name="ignition::gazebo::systems::UserCommands">
</plugin>
<plugin
filename="ignition-gazebo-scene-broadcaster-system"
name="ignition::gazebo::systems::SceneBroadcaster">
</plugin>

<scene>
<ambient>1.0 1.0 1.0</ambient>
<background>0.8 0.8 0.8</background>
<sky></sky>
</scene>

<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
<direction>0.0 0.6 -0.9</direction>
</light>

<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
</plane>
</geometry>
</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>
</link>
</model>

<model name="box">
<pose>0 0 0.5 0 0 0</pose>
<link name="box_link">
<inertial>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
<mass>1.0</mass>
</inertial>
<collision name="box_collision">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</collision>

<visual name="box_visual">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>1 0 0 1</diffuse>
<specular>1 0 0 1</specular>
</material>
</visual>
</link>
</model>

<model name="cylinder">
<pose>0 -1.5 0.5 0 0 0</pose>
<link name="cylinder_link">
<inertial>
<inertia>
<ixx>2</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>2</iyy>
<iyz>0</iyz>
<izz>2</izz>
</inertia>
<mass>2.0</mass>
</inertial>
<collision name="cylinder_collision">
<geometry>
<cylinder>
<radius>0.5</radius>
<length>1.0</length>
</cylinder>
</geometry>
</collision>

<visual name="cylinder_visual">
<geometry>
<cylinder>
<radius>0.5</radius>
<length>1.0</length>
</cylinder>
</geometry>
<material>
<ambient>0 1 0 1</ambient>
<diffuse>0 1 0 1</diffuse>
<specular>0 1 0 1</specular>
</material>
</visual>
</link>
</model>

<model name="sphere">
<pose>0 1.5 0.5 0 0 0</pose>
<link name="sphere_link">
<inertial>
<inertia>
<ixx>3</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>3</iyy>
<iyz>0</iyz>
<izz>3</izz>
</inertia>
<mass>3.0</mass>
</inertial>
<collision name="sphere_collision">
<geometry>
<sphere>
<radius>0.5</radius>
</sphere>
</geometry>
</collision>

<visual name="sphere_visual">
<geometry>
<sphere>
<radius>0.5</radius>
</sphere>
</geometry>
<material>
<ambient>0 0 1 1</ambient>
<diffuse>0 0 1 1</diffuse>
<specular>0 0 1 1</specular>
</material>
</visual>
</link>
</model>

<model name="camera">
<static>true</static>
<pose>-3 0 0.5 0 0.0 0</pose>
<link name="link">
<pose>0.05 0.05 0.05 0 0 0</pose>
<collision name="collision">
<geometry>
<box>
<size>0.1 0.1 0.1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>0.1 0.1 0.1</size>
</box>
</geometry>
</visual>
<sensor name="camera" type="camera">
<camera>
<horizontal_fov>1.047</horizontal_fov>
<image>
<width>320</width>
<height>240</height>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>true</visualize>
<topic>camera</topic>
</sensor>
</link>
</model>

</world>
</sdf>

4 changes: 4 additions & 0 deletions include/ignition/gazebo/rendering/RenderUtil.hh
Original file line number Diff line number Diff line change
Expand Up @@ -94,6 +94,10 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
/// \param[in] _ambient Color of ambient light
public: void SetAmbientLight(const math::Color &_ambient);

/// \brief Set whether to enable sky in the scene
/// \param[in] _enabled True to enable sky, false to disable sky
public: void SetSkyEnabled(bool _enabled);

/// \brief Show grid view in the scene
public: void ShowGrid();

Expand Down
29 changes: 29 additions & 0 deletions src/Conversions.cc
Original file line number Diff line number Diff line change
Expand Up @@ -624,6 +624,21 @@ msgs::Scene ignition::gazebo::convert(const sdf::Scene &_in)
out.set_shadows(_in.Shadows());
out.set_grid(_in.Grid());
out.set_origin_visual(_in.OriginVisual());

if (_in.Sky())
{
msgs::Sky *skyMsg = out.mutable_sky();
skyMsg->set_time(_in.Sky()->Time());
skyMsg->set_sunrise(_in.Sky()->Sunrise());
skyMsg->set_sunset(_in.Sky()->Sunset());
skyMsg->set_wind_speed(_in.Sky()->CloudSpeed());
skyMsg->set_wind_direction(_in.Sky()->CloudDirection().Radian());
skyMsg->set_humidity(_in.Sky()->CloudHumidity());
skyMsg->set_mean_cloud_size(_in.Sky()->CloudMeanSize());
msgs::Set(skyMsg->mutable_cloud_ambient(),
_in.Sky()->CloudAmbient());
}

return out;
}

Expand All @@ -639,6 +654,20 @@ sdf::Scene ignition::gazebo::convert(const msgs::Scene &_in)
out.SetShadows(_in.shadows());
out.SetGrid(_in.grid());
out.SetOriginVisual(_in.origin_visual());

if (_in.has_sky())
{
sdf::Sky sky;
sky.SetTime(_in.sky().time());
sky.SetSunrise(_in.sky().sunrise());
sky.SetSunset(_in.sky().sunset());
sky.SetCloudSpeed(_in.sky().wind_speed());
sky.SetCloudDirection(math::Angle(_in.sky().wind_direction()));
sky.SetCloudHumidity(_in.sky().humidity());
sky.SetCloudMeanSize(_in.sky().mean_cloud_size());
sky.SetCloudAmbient(msgs::Convert(_in.sky().cloud_ambient()));
out.SetSky(sky);
}
return out;
}

Expand Down
Loading