Skip to content

Commit

Permalink
4 ➡️ 5 (#622)
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <[email protected]>
  • Loading branch information
chapulina authored Mar 3, 2021
2 parents 7b290ec + dc60a3a commit 6c91ff9
Show file tree
Hide file tree
Showing 205 changed files with 12,279 additions and 494 deletions.
1 change: 1 addition & 0 deletions .github/ci/after_make.sh
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@ set -e

# Install (needed for some tests)
make install
export LD_LIBRARY_PATH=${LD_LIBRARY_PATH}:/usr/local/lib

# For ign-tools
export IGN_CONFIG_PATH=/usr/local/share/ignition
Expand Down
93 changes: 93 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
@@ -1,5 +1,98 @@
## Ignition Gazebo 4.x

### Ignition Gazebo 4.5.0 (2020-02-17)

1. Added particle system.
* [Pull Request 516](https:/ignitionrobotics/ign-gazebo/pull/516)

1. Add Light Usercommand and include Light parameters in the componentInspector
* [Pull Request 482](https:/ignitionrobotics/ign-gazebo/pull/482)

1. Added link to HW-accelerated video recording.
* [Pull Request 627](https:/ignitionrobotics/ign-gazebo/pull/627)

1. Fix EntityComponentManager race condition.
* [Pull Request 601](https:/ignitionrobotics/ign-gazebo/pull/601)

1. Add SDF topic validity check.
* [Pull Request 632](https:/ignitionrobotics/ign-gazebo/pull/632)

1. Add JointTrajectoryController system plugin.
* [Pull Request 473](https:/ignitionrobotics/ign-gazebo/pull/473)

### Ignition Gazebo 4.4.0 (2020-02-10)

1. Added issue and PR templates
* [Pull Request 613](https:/ignitionrobotics/ign-gazebo/pull/613)

1. Fix segfault in SetRemovedComponentsMsgs method
* [Pull Request 495](https:/ignitionrobotics/ign-gazebo/pull/495)

1. Make topics configurable for joint controllers
* [Pull Request 584](https:/ignitionrobotics/ign-gazebo/pull/584)

1. Add about dialog
* [Pull Request 609](https:/ignitionrobotics/ign-gazebo/pull/609)

1. Add thermal sensor system for configuring thermal camera properties
* [Pull Request 614](https:/ignitionrobotics/ign-gazebo/pull/614)

### Ignition Gazebo 4.3.0 (2020-02-02)

1. Non-blocking paths request.
* [Pull Request 555](https:/ignitionrobotics/ign-gazebo/pull/555)

1. Parallelize State call in ECM.
* [Pull Request 451](https:/ignitionrobotics/ign-gazebo/pull/451)

1. Allow to create light with the create service.
* [Pull Request 513](https:/ignitionrobotics/ign-gazebo/pull/513)

1. Added size to ground_plane in examples.
* [Pull Request 573](https:/ignitionrobotics/ign-gazebo/pull/573)

1. Fix finding PBR materials.
* [Pull Request 575](https:/ignitionrobotics/ign-gazebo/pull/575)

1. Publish all periodic change components in Scene Broadcaster.
* [Pull Request 544](https:/ignitionrobotics/ign-gazebo/pull/544)

1. Backport state update changes from pull request [#486](https:/ignitionrobotics/ign-gazebo/pull/486).
* [Pull Request 583](https:/ignitionrobotics/ign-gazebo/pull/583)

1. Fix code_check errors.
* [Pull Request 582](https:/ignitionrobotics/ign-gazebo/pull/582)

1. Visualize collisions.
* [Pull Request 531](https:/ignitionrobotics/ign-gazebo/pull/531)

1. Remove playback <path> SDF param in Dome.
* [Pull Request 570](https:/ignitionrobotics/ign-gazebo/pull/570)

1. Tutorial on migrating SDF files from Gazebo classic.
* [Pull Request 400](https:/ignitionrobotics/ign-gazebo/pull/400)

1. World Exporter.
* [Pull Request 474](https:/ignitionrobotics/ign-gazebo/pull/474)

1. Model Creation tutorial using services.
* [Pull Request 530](https:/ignitionrobotics/ign-gazebo/pull/530)

1. Fix topLevelModel Method.
* [Pull Request 600](https:/ignitionrobotics/ign-gazebo/pull/600)

1. Add heat signature option to thermal system.
* [Pull Request 498](https:/ignitionrobotics/ign-gazebo/pull/498)

1. Add service and GUI to configure physics parameters (step size and RTF).
* [Pull Request 536](https:/ignitionrobotics/ign-gazebo/pull/536)

1. Refactor UNIT_Server_TEST.
* [Pull Request 594](https:/ignitionrobotics/ign-gazebo/pull/594)

1. Use Ignition GUI render event.
* [Pull Request 598](https:/ignitionrobotics/ign-gazebo/pull/598)

### Ignition Gazebo 4.2.0 (2020-01-13)

1. Automatically load a subset of world plugins.
Expand Down
7 changes: 7 additions & 0 deletions Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,13 @@ in SDF by setting the `<visual><material><double_sided>` SDF element.
std::string(const gazebo::Entity &,
const sdf::Sensor &, const std::string &)>)`

* Log playback using `<path>` SDF parameter is removed. Use --playback command
line argument instead.

* `rendering::SceneManager`
* **Deprecated**: `Entity EntityFromNode(const rendering::NodePtr &_node) const;`
* **Replacement**: `Entity entity = std::get<int>(visual->UserData("gazebo-entity"));`

## Ignition Gazebo 2.x to 3.x

* Use ign-rendering3, ign-sensors3 and ign-gui3.
Expand Down
1 change: 1 addition & 0 deletions examples/scripts/distributed/secondary.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
</collision>
Expand Down
1 change: 1 addition & 0 deletions examples/scripts/distributed/standalone.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -108,6 +108,7 @@
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
</collision>
Expand Down
8 changes: 8 additions & 0 deletions examples/standalone/entity_creation/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR)

find_package(ignition-transport10 QUIET REQUIRED OPTIONAL_COMPONENTS log)
set(IGN_TRANSPORT_VER ${ignition-transport10_VERSION_MAJOR})

add_executable(entity_creation entity_creation.cc)
target_link_libraries(entity_creation
ignition-transport${IGN_TRANSPORT_VER}::core)
25 changes: 25 additions & 0 deletions examples/standalone/entity_creation/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
# Examples using the create service

## Build

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

## Run

This example only works if the world is called `empty`. Start an empty world with:

```
ign gazebo empty.sdf
```

Then run the create program to spawn entities into the world:

```
cd build
./entity_creation
```
186 changes: 186 additions & 0 deletions examples/standalone/entity_creation/entity_creation.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,186 @@
/*
* Copyright (C) 2021 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 <ignition/msgs/entity_factory.pb.h>

#include <iostream>

#include <ignition/transport/Node.hh>

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

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

void createLight()
{
bool result;
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(0.5, 0.2, -0.9));
ignition::msgs::Set(entityFactoryRequest.mutable_light()->mutable_pose(),
ignition::math::Pose3d(0.0, 0, 3.0, 0.0, 0.0, 0.0));
//! [create light]

//! [call service create]
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;
//! [call service create]
}

void createEntityFromStr(const std::string modelStr)
{
//! [call service create sphere]
bool result;
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;
//! [call service create sphere]
}

//////////////////////////////////////////////////
std::string generateLightStr(
const std::string light_type, const std::string name,
const bool cast_shadows, const ignition::math::Pose3d pose,
const ignition::math::Color diffuse,
const ignition::math::Color specular,
const double attRange, const double attConstant,
const double attLinear, const double attQuadratic,
const ignition::math::Vector3d direction,
const double spot_inner_angle,
const double spot_outer_angle,
const double spot_falloff
)
{
//! [create light str]
std::string lightStr = std::string("<sdf version='1.7'>") +
"<light type='" + light_type + "' name='" + name + "'> " +
"<cast_shadows>" + std::to_string(cast_shadows) + "</cast_shadows>" +
"<pose>" +
std::to_string(pose.Pos().X()) + " " +
std::to_string(pose.Pos().Y()) + " " +
std::to_string(pose.Pos().Z()) + " " +
std::to_string(pose.Rot().Roll()) + " " +
std::to_string(pose.Rot().Pitch()) + " " +
std::to_string(pose.Rot().Yaw()) +
"</pose>" +
"<diffuse>" +
std::to_string(diffuse.R()) + " " +
std::to_string(diffuse.G()) + " " +
std::to_string(diffuse.B()) + " " +
std::to_string(diffuse.A()) +
"</diffuse>" +
"<specular>" +
std::to_string(specular.R()) + " " +
std::to_string(specular.G()) + " " +
std::to_string(specular.B()) + " " +
std::to_string(specular.A()) +
"</specular>" +
"<attenuation>" +
"<range>" + std::to_string(attRange) + "</range>" +
"<constant>" + std::to_string(attConstant) + "</constant>" +
"<linear>" + std::to_string(attLinear) + "</linear>" +
"<quadratic>" + std::to_string(attQuadratic) + "</quadratic>" +
"</attenuation>" +
"<direction>" +
std::to_string(direction.X()) + " " +
std::to_string(direction.Y()) + " " +
std::to_string(direction.Z()) +
"</direction>" +
"<spot>" +
"<inner_angle>" + std::to_string(spot_inner_angle) + "</inner_angle>" +
"<outer_angle>" + std::to_string(spot_outer_angle) + "</outer_angle>" +
"<falloff>" + std::to_string(spot_falloff) + "</falloff>" +
"</spot>" +
"</light></sdf>";
//! [create light str]
return lightStr;
}

//////////////////////////////////////////////////
int main(int argc, char **argv)
{
//! [create sphere]
auto sphereStr = 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>)";
//! [create sphere]

createEntityFromStr(sphereStr);

createEntityFromStr(
generateLightStr("spot", "spot_light", false,
ignition::math::Pose3d(0, 0, 4, 0, 0, 0),
ignition::math::Color(0, 0, 1.0, 1.0),
ignition::math::Color(0, 0, 1.0, 1.0),
1.0, 0.2, 0.2, 0.001,
ignition::math::Vector3d(0.5, 0.2, -0.9),
0.15, 0.45, 1.0));

createLight();
}
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-transport10 QUIET REQUIRED OPTIONAL_COMPONENTS log)
set(IGN_TRANSPORT_VER ${ignition-transport10_VERSION_MAJOR})

find_package(ignition-gazebo5 REQUIRED)
set(IGN_GAZEBO_VER ${ignition-gazebo5_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})
Loading

0 comments on commit 6c91ff9

Please sign in to comment.