Skip to content

Commit

Permalink
4 ➡️ 5 (#877)
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <louise@openrobotics.org>
  • Loading branch information
chapulina authored Jun 25, 2021
2 parents 3e2018e + acc627a commit ee6a29e
Show file tree
Hide file tree
Showing 84 changed files with 3,529 additions and 8,138 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/ci.yml
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ jobs:
id: ci
uses: ignition-tooling/action-ignition-ci@bionic
with:
codecov-token: ${{ secrets.CODECOV_TOKEN }}
codecov-enabled: true
focal-ci:
runs-on: ubuntu-latest
name: Ubuntu Focal CI
Expand Down
8 changes: 4 additions & 4 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ project(ignition-gazebo5 VERSION 5.0.0)
# Find ignition-cmake
#============================================================================
# If you get an error at this line, you need to install ignition-cmake
find_package(ignition-cmake2 2.3 REQUIRED)
find_package(ignition-cmake2 2.8.0 REQUIRED)

#============================================================================
# Configure the project
Expand Down Expand Up @@ -38,7 +38,7 @@ endif()
# Search for project-specific dependencies
#============================================================================

ign_find_package(sdformat11 REQUIRED VERSION 11.1)
ign_find_package(sdformat11 REQUIRED VERSION 11.2)
set(SDF_VER ${sdformat11_VERSION_MAJOR})

#--------------------------------------
Expand Down Expand Up @@ -75,7 +75,7 @@ set(IGN_FUEL_TOOLS_VER ${ignition-fuel_tools6_VERSION_MAJOR})

#--------------------------------------
# Find ignition-gui
ign_find_package(ignition-gui5 REQUIRED)
ign_find_package(ignition-gui5 REQUIRED VERSION 5.1)
set(IGN_GUI_VER ${ignition-gui5_VERSION_MAJOR})
ign_find_package (Qt5
COMPONENTS
Expand Down Expand Up @@ -114,7 +114,7 @@ set(IGN_SENSORS_VER ${ignition-sensors5_VERSION_MAJOR})

#--------------------------------------
# Find ignition-rendering
ign_find_package(ignition-rendering5 REQUIRED)
ign_find_package(ignition-rendering5 REQUIRED VERSION 5.1)
set(IGN_RENDERING_VER ${ignition-rendering5_VERSION_MAJOR})

#--------------------------------------
Expand Down
43 changes: 43 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -137,6 +137,49 @@

### Ignition Gazebo 4.x.x (202x-xx-xx)

### Ignition Gazebo 4.9.1 (2021-05-24)

1. Make halt motion act like a brake.
* [Pull Request 830](https://github.com/ignitionrobotics/ign-gazebo/pull/830)

### Ignition Gazebo 4.9.0 (2021-05-20)

1. Enable Focal CI.
* [Pull Request 646](https://github.com/ignitionrobotics/ign-gazebo/pull/646)

1. [TPE] Support setting individual link velocity.
* [Pull Request 427](https://github.com/ignitionrobotics/ign-gazebo/pull/427)

1. Don't store duplicate ComponentTypeId in ECM.
* [Pull Request 751](https://github.com/ignitionrobotics/ign-gazebo/pull/751)

1. Fix macOS build: components::Name in benchmark.
* [Pull Request 784](https://github.com/ignitionrobotics/ign-gazebo/pull/784)

1. Fix documentation for EntityComponentManager::EachNew.
* [Pull Request 795](https://github.com/ignitionrobotics/ign-gazebo/pull/795)

1. Add functionalities for optical tactile plugin.
* [Pull Request 431](https://github.com/ignitionrobotics/ign-gazebo/pull/431)

1. Visualize ContactSensorData.
* [Pull Request 234](https://github.com/ignitionrobotics/ign-gazebo/pull/234)

1. Backport PR #763.
* [Pull Request 804](https://github.com/ignitionrobotics/ign-gazebo/pull/804)

1. Backport PR #536.
* [Pull Request 812](https://github.com/ignitionrobotics/ign-gazebo/pull/812)

1. Add an optional delay to the TriggeredPublisher system.
* [Pull Request 817](https://github.com/ignitionrobotics/ign-gazebo/pull/817)

1. Remove tools/code_check and update codecov.
* [Pull Request 814](https://github.com/ignitionrobotics/ign-gazebo/pull/814)

1. add conversion for particle scatter ratio field.
* [Pull Request 791](https://github.com/ignitionrobotics/ign-gazebo/pull/791)

### Ignition Gazebo 4.8.0 (2021-04-22)

1. Add odometry publisher system.
Expand Down
7 changes: 7 additions & 0 deletions examples/standalone/external_ecm/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR)

find_package(ignition-gazebo5 REQUIRED)

add_executable(external_ecm external_ecm.cc)
target_link_libraries(external_ecm
ignition-gazebo5::core)
93 changes: 93 additions & 0 deletions examples/standalone/external_ecm/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,93 @@
# External ECM

Example showing how to get a snapshot of all entities and components in a
running simulation from an external program using the state message.

## Build

From the root of the `ign-gazebo` repository, do the following to build the example:

~~~
cd ign-gazebo/examples/standalone/external_ecm
mkdir build
cd build
cmake ..
make
~~~

This will generate the `external_ecm` executable under `build`.

## Run

Start a simulation, for example:

ign gazebo shapes.sdf

On another terminal, run the `external_ecm` executable, passing the name of the
running world you want to inspect:

cd ign-gazebo/examples/standalone/external_ecm
./external_ecm shapes

You should see something like this:

```
$ ./external_ecm shapes
Requesting state for world [shapes] on service [/world/shapes/state]...
Entity [1]
- Name: shapes
- Parent:
Entity [4]
- Name: ground_plane
- Parent: shapes [1]
Entity [5]
- Name: link
- Parent: ground_plane [4]
Entity [6]
- Name: visual
- Parent: link [5]
Entity [7]
- Name: collision
- Parent: link [5]
Entity [8]
- Name: box
- Parent: shapes [1]
Entity [9]
- Name: box_link
- Parent: box [8]
Entity [10]
- Name: box_visual
- Parent: box_link [9]
Entity [11]
- Name: box_collision
- Parent: box_link [9]
Entity [12]
- Name: cylinder
- Parent: shapes [1]
Entity [13]
- Name: cylinder_link
- Parent: cylinder [12]
Entity [14]
- Name: cylinder_visual
- Parent: cylinder_link [13]
Entity [15]
- Name: cylinder_collision
- Parent: cylinder_link [13]
Entity [16]
- Name: sphere
- Parent: shapes [1]
Entity [17]
- Name: sphere_link
- Parent: sphere [16]
Entity [18]
- Name: sphere_visual
- Parent: sphere_link [17]
Entity [19]
- Name: sphere_collision
- Parent: sphere_link [17]
Entity [20]
- Name: sun
- Parent: shapes [1]
```
98 changes: 98 additions & 0 deletions examples/standalone/external_ecm/external_ecm.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,98 @@
/*
* 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 <iostream>
#include <ignition/gazebo/EntityComponentManager.hh>
#include <ignition/gazebo/components/Name.hh>
#include <ignition/gazebo/components/ParentEntity.hh>
#include <ignition/msgs/serialized.pb.h>
#include <ignition/transport/Node.hh>

//////////////////////////////////////////////////
int main(int argc, char **argv)
{
if (argc < 2)
{
std::cout << "Usage: `./external_ecm <world name>`" << std::endl;
return -1;
}

// Get arguments
std::string world = argv[1];

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

bool executed{false};
bool result{false};
unsigned int timeout{5000};
std::string service{"/world/" + world + "/state"};

std::cout << std::endl << "Requesting state for world [" << world
<< "] on service [" << service << "]..." << std::endl << std::endl;

// Request and block
ignition::msgs::SerializedStepMap res;
executed = node.Request(service, timeout, res, result);

if (!executed)
{
std::cerr << std::endl << "Service call to [" << service << "] timed out"
<< std::endl;
return -1;
}

if (!result)
{
std::cerr << std::endl << "Service call to [" << service << "] failed"
<< std::endl;
return -1;
}

// Instantiate an ECM and populate with data from message
ignition::gazebo::EntityComponentManager ecm;
ecm.SetState(res.state());

// Print some information
ecm.Each<ignition::gazebo::components::Name>(
[&](const ignition::gazebo::Entity &_entity,
const ignition::gazebo::components::Name *_name) -> bool
{
auto parentComp =
ecm.Component<ignition::gazebo::components::ParentEntity>(_entity);

std::string parentInfo;
if (parentComp)
{
auto parentNameComp =
ecm.Component<ignition::gazebo::components::Name>(
parentComp->Data());

if (parentNameComp)
{
parentInfo += parentNameComp->Data() + " ";
}
parentInfo += "[" + std::to_string(parentComp->Data()) + "]";
}

std::cout << "Entity [" << _entity << "]" << std::endl
<< " - Name: " << _name->Data() << std::endl
<< " - Parent: " << parentInfo << std::endl;

return true;
});
}
26 changes: 21 additions & 5 deletions examples/worlds/optical_tactile_sensor_plugin.sdf
Original file line number Diff line number Diff line change
@@ -1,4 +1,17 @@
<?xml version="1.0" ?>
<!--
Demo of an optical tactile plugin.
Move the tactile sensor to touch different objects and see the output.
Disable the sensor with:
ign service -s /optical_tactile_plugin/enable \
--reqtype ignition.msgs.Boolean \
--reptype ignition.msgs.Empty \
--timeout 2000 --req 'data: false'
-->

<sdf version="1.7">
<world name="optical_tactile_plugin">
Expand Down Expand Up @@ -38,7 +51,8 @@
<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_pose>0.35 0.23 0.94 0 0.05 -2.53</camera_pose>

</plugin>

<!-- World control -->
Expand Down Expand Up @@ -196,14 +210,16 @@
</sensor>

</link>
<static>true</static>
<static>false</static>
<plugin
filename="libignition-gazebo-opticaltactileplugin-system.so"
name="ignition::gazebo::systems::OpticalTactilePlugin">
<enabled>true</enabled>
<visualization_resolution>15</visualization_resolution>
<visualize_forces>true</visualize_forces>
<namespace>optical_tactile_plugin</namespace>
<visualize_sensor>true</visualize_sensor>
<visualize_contacts>true</visualize_contacts>
<visualize_forces>true</visualize_forces>
<visualization_resolution>15</visualization_resolution>
<force_length>0.01</force_length>
<extended_sensing>0.001</extended_sensing>
</plugin>
Expand All @@ -223,7 +239,7 @@
<pose>0 -0.7 0 0 0 3.14</pose>
<uri>https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/OfficeChairBlue</uri>
</include>

<include>
<pose>-1.5 0 0 0 0 0</pose>
<uri>https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/VendingMachine</uri>
Expand Down
6 changes: 4 additions & 2 deletions examples/worlds/triggered_publisher.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,9 @@ Send the command:
ign topic -t "/start" -m ignition.msgs.Empty -p " "
The vehicle should start moving while the two boxes remain floating. When the
vehicle crosses the line on the ground, the first box should start falling. The
moment the box hits the ground, the second box should start falling.
vehicle crosses the line on the ground, the first box should start falling.
Five simulation seconds after the box hits the ground, the second box should
start falling.
-->
<sdf version="1.6">
Expand Down Expand Up @@ -529,6 +530,7 @@ moment the box hits the ground, the second box should start falling.
<input type="ignition.msgs.Altimeter" topic="/altimeter">
<match field="vertical_position" tol="0.2">-7.5</match>
</input>
<delay_ms>5000</delay_ms>
<output type="ignition.msgs.Empty" topic="/box2/detach"/>
</plugin>
</world>
Expand Down
Loading

0 comments on commit ee6a29e

Please sign in to comment.