Skip to content

Commit

Permalink
Added light tutorial and example (#515)
Browse files Browse the repository at this point in the history
* Added light tutorial and example

Signed-off-by: ahcorde <[email protected]>

* Added some feedback

Signed-off-by: ahcorde <[email protected]>

* Split tutorial in two

Signed-off-by: ahcorde <[email protected]>

* remove ids from tutorial

Signed-off-by: ahcorde <[email protected]>

* Added feedback

Signed-off-by: ahcorde <[email protected]>

* update tutorial

Signed-off-by: ahcorde <[email protected]>

Co-authored-by: Louise Poubel <[email protected]>
  • Loading branch information
ahcorde and chapulina authored Feb 2, 2021
1 parent 5eb2bb1 commit 53f045b
Show file tree
Hide file tree
Showing 4 changed files with 237 additions and 0 deletions.
12 changes: 12 additions & 0 deletions examples/standalone/light_control/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR)

find_package(ignition-transport9 QUIET REQUIRED OPTIONAL_COMPONENTS log)
set(IGN_TRANSPORT_VER ${ignition-transport9_VERSION_MAJOR})

find_package(ignition-gazebo4 REQUIRED)
set(IGN_GAZEBO_VER ${ignition-gazebo4_VERSION_MAJOR})

add_executable(light_control light_control.cc)
target_link_libraries(light_control
ignition-transport${IGN_TRANSPORT_VER}::core
ignition-gazebo${IGN_GAZEBO_VER}::ignition-gazebo${IGN_GAZEBO_VER})
179 changes: 179 additions & 0 deletions examples/standalone/light_control/light_control.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,179 @@
/*
* Copyright (C) 2020 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/

#include <chrono>
#include <iostream>

#include <ignition/gazebo/components/Light.hh>
#include <ignition/gazebo/components/LightCmd.hh>
#include <ignition/msgs.hh>
#include <ignition/transport.hh>

using namespace std::chrono_literals;

// Create a transport node.
ignition::transport::Node node;

bool result;
// timeout used for services
constexpr unsigned int timeout = 5000;

std::mt19937 twister(std::time(0));
std::uniform_real_distribution<double> distr(0, 1000);
constexpr double epsilon = 0.1;

float directionX = 0.5;
float directionY = 0.2;
float directionZ = -0.9;

void createLight()
{
ignition::msgs::Boolean rep;
//! [create light]
ignition::msgs::EntityFactory entityFactoryRequest;

entityFactoryRequest.mutable_light()->set_name("point");
entityFactoryRequest.mutable_light()->set_range(4);
entityFactoryRequest.mutable_light()->set_attenuation_linear(0.5);
entityFactoryRequest.mutable_light()->set_attenuation_constant(0.2);
entityFactoryRequest.mutable_light()->set_attenuation_quadratic(0.01);
entityFactoryRequest.mutable_light()->set_cast_shadows(false);
entityFactoryRequest.mutable_light()->set_type(ignition::msgs::Light::POINT);
ignition::msgs::Set(
entityFactoryRequest.mutable_light()->mutable_direction(),
ignition::math::Vector3d(directionX, directionY, directionZ));
ignition::msgs::Set(entityFactoryRequest.mutable_light()->mutable_pose(),
ignition::math::Pose3d(0.0, 0, 3.0, 0.0, 0.0, 0.0));
//! [create light]

bool executedEntityFactory = node.Request("/world/empty/create",
entityFactoryRequest, timeout, rep, result);
if (executedEntityFactory)
{
if (result)
std::cout << "Light was created : [" << rep.data() << "]" << std::endl;
else
{
std::cout << "Service call failed" << std::endl;
return;
}
}
else
std::cerr << "Service call timed out" << std::endl;
}

void createSphere()
{
auto modelStr = R"(
<?xml version="1.0" ?>
<sdf version='1.7'>
<model name='sphere'>
<link name='link'>
<pose>0 0 0.5 0 0 0</pose>
<visual name='visual'>
<geometry><sphere><radius>1</radius></sphere></geometry>
</visual>
<collision name='collision'>
<geometry><sphere><radius>1</radius></sphere></geometry>
</collision>
</link>
</model>
</sdf>)";

ignition::msgs::EntityFactory req;
ignition::msgs::Boolean res;
req.set_sdf(modelStr);

bool executed = node.Request("/world/empty/create",
req, timeout, res, result);
if (executed)
{
if (result)
std::cout << "Sphere was created : [" << res.data() << "]" << std::endl;
else
{
std::cout << "Service call failed" << std::endl;
return;
}
}
else
std::cerr << "Service call timed out" << std::endl;
}

//////////////////////////////////////////////////
int main(int argc, char **argv)
{
ignition::msgs::Boolean rep;
ignition::msgs::Light lightRequest;
auto lightConfigService = "/world/empty/light_config";

createSphere();
createLight();

while (1)
{
float r, g, b;
double m = 0;
//! [random numbers]
while (m < epsilon)
{
r = distr(twister);
g = distr(twister);
b = distr(twister);
m = std::sqrt(r*r + b*b + g*g);
}
r /= m;
b /= m;
b /= m;
//! [random numbers]

//! [modify light]
lightRequest.set_name("point");
lightRequest.set_range(4);
lightRequest.set_attenuation_linear(0.5);
lightRequest.set_attenuation_constant(0.2);
lightRequest.set_attenuation_quadratic(0.01);
lightRequest.set_cast_shadows(false);
lightRequest.set_type(ignition::msgs::Light::POINT);
// direction field only affects spot / directional lights
ignition::msgs::Set(lightRequest.mutable_direction(),
ignition::math::Vector3d(directionX, directionY, directionZ));
ignition::msgs::Set(lightRequest.mutable_pose(),
ignition::math::Pose3d(0.0, -1.5, 3.0, 0.0, 0.0, 0.0));
ignition::msgs::Set(lightRequest.mutable_diffuse(),
ignition::math::Color(r, g, b, 1));
ignition::msgs::Set(lightRequest.mutable_specular(),
ignition::math::Color(r, g, b, 1));
//! [modify light]
bool executed = node.Request(lightConfigService, lightRequest, timeout,
rep, result);
std::cout << "Service called: [" << r << ", " << g << ", " << b << "]"
<< std::endl;

if (executed)
{
if (result)
std::cout << "Response: [" << rep.data() << "]" << std::endl;
else
std::cout << "Service call failed" << std::endl;
}
else
std::cerr << "Service call timed out" << std::endl;

std::this_thread::sleep_for(1s);
}
}
1 change: 1 addition & 0 deletions tutorials.md.in
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@ Ignition @IGN_DESIGNATION_CAP@ library and how to use the library effectively.
* \subpage resources "Finding resources": The different ways in which Ignition looks for files.
* \subpage log "Logging": Record and play back time series of world state.
* \subpage physics "Physics engines": Loading different physics engines.
* \subpage light_config "Light config": Configure lights in the scene.
* \subpage battery "Battery": Keep track of battery charge on robot models.
* \subpage gui_config "GUI configuration": Customizing your layout.
* \subpage server_config "Server configuration": Customizing what system plugins are loaded.
Expand Down
45 changes: 45 additions & 0 deletions tutorials/light_config.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
\page light_config Light config

This tutorial gives an introduction to the Ignition Gazebo's service `/world/<world name>/light_config`.
This service will allow to modify lights in the scene.

# Modifying lights

To modify lights inside the scene we need to use the service `/world/<world name>/light_config` and
fill the message [`ignition::msgs::Light`](https://ignitionrobotics.org/api/msgs/6.0/classignition_1_1msgs_1_1Light.html).
In particular this example modify the point light that we introduced with the function `createLight()`.

\snippet examples/standalone/light_control/light_control.cc create light

**NOTE:**: You can check the [model creation](model_creation.html) tutorial to learn how to include models and lights in the scene.

As you can see in the snippet we modify the specular and diffuse of the light that corresponds to type of light in the scene.

\snippet examples/standalone/light_control/light_control.cc modify light

In this case we are creating random numbers to fill the diffuse and specular.

\snippet examples/standalone/light_control/light_control.cc random numbers

# Run the example

To run this example you should `cd` into `examples/standalone/light_control` and build the code:

```bash
mkdir build
cd build
cmake ..
make
```

Then you should open two terminals and run:

- Terminal one:
```bash
ign gazebo -r -v 4 empty.world
```

- Terminal two:
```bash
./light_control
```

0 comments on commit 53f045b

Please sign in to comment.