Skip to content

Commit

Permalink
6 ➡️ 7 (main) (#1446)
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <louise@openrobotics.org>
  • Loading branch information
chapulina authored Apr 25, 2022
2 parents 1083313 + e399431 commit 7063d41
Show file tree
Hide file tree
Showing 44 changed files with 3,966 additions and 53 deletions.
4 changes: 0 additions & 4 deletions .github/ci/packages-bionic.apt

This file was deleted.

1 change: 1 addition & 0 deletions .github/ci/packages-focal.apt
Original file line number Diff line number Diff line change
Expand Up @@ -3,4 +3,5 @@ libdart-dev
libdart-external-ikfast-dev
libdart-external-odelcpsolver-dev
libdart-utils-urdf-dev
libogre-2.2-dev
python3-ignition-math7
7 changes: 7 additions & 0 deletions .github/ci/packages-jammy.apt
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
libdart-collision-ode-dev
libdart-dev
libdart-external-ikfast-dev
libdart-external-odelcpsolver-dev
libdart-utils-urdf-dev
libogre-next-dev
python3-ignition-math7
1 change: 0 additions & 1 deletion .github/ci/packages.apt
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@ libignition-tools2-dev
libignition-transport12-dev
libignition-utils2-cli-dev
libogre-1.9-dev
libogre-2.2-dev
libprotobuf-dev
libprotoc-dev
libsdformat13-dev
Expand Down
12 changes: 12 additions & 0 deletions .github/workflows/ci.yml
Original file line number Diff line number Diff line change
Expand Up @@ -16,3 +16,15 @@ jobs:
codecov-enabled: true
cppcheck-enabled: true
cpplint-enabled: true
jammy-ci:
runs-on: ubuntu-latest
name: Ubuntu Jammy CI
steps:
- name: Checkout
uses: actions/checkout@v2
- name: Compile and test
id: ci
uses: ignition-tooling/action-ignition-ci@jammy
with:
# per bug https://github.com/ignitionrobotics/ign-gazebo/issues/1409
cmake-args: '-DBUILD_DOCS=OFF'
2 changes: 2 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -226,6 +226,8 @@ endif()
#============================================================================
configure_file(${CMAKE_SOURCE_DIR}/api.md.in ${CMAKE_BINARY_DIR}/api.md)
configure_file(${CMAKE_SOURCE_DIR}/tutorials.md.in ${CMAKE_BINARY_DIR}/tutorials.md)
configure_file(${CMAKE_SOURCE_DIR}/tools/desktop/ignition-gazebo.desktop.in ${CMAKE_BINARY_DIR}/ignition-gazebo${PROJECT_VERSION_MAJOR}.desktop)
configure_file(${CMAKE_SOURCE_DIR}/tools/desktop/ignition-gazebo.svg.in ${CMAKE_BINARY_DIR}/ignition-gazebo${PROJECT_VERSION_MAJOR}.svg)

# disable doxygen on macOS due to issues with doxygen 1.9.0
# there is an unreleased fix; revert this when 1.9.1 is released
Expand Down
33 changes: 33 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,39 @@

## Ignition Gazebo 6.x

### Ignition Gazebo 6.9.0 (2022-04-14)

1. Add new `RFComms` system
* [Pull request #1428](https://github.com/ignitionrobotics/ign-gazebo/pull/1428)

1. Add comms infrastructure
* [Pull request #1416](https://github.com/ignitionrobotics/ign-gazebo/pull/1416)

1. Fix CMake version examples and bump plugin version
* [Pull request #1442](https://github.com/ignitionrobotics/ign-gazebo/pull/1442)

1. Make sure pose publisher creates valid pose topics
* [Pull request #1433](https://github.com/ignitionrobotics/ign-gazebo/pull/1433)

1. Add Ubuntu Jammy CI
* [Pull request #1418](https://github.com/ignitionrobotics/ign-gazebo/pull/1418)

1. Removed `screenToPlane` method and use `rendering::screenToPlane`
* [Pull request #1432](https://github.com/ignitionrobotics/ign-gazebo/pull/1432)

1. Supply world frame orientation and heading to IMU sensor (#1427)
* [Pull request #1427](https://github.com/ignitionrobotics/ign-gazebo/pull/1427)

1. Add desktop entry and SVG logo
* [Pull request #1411](https://github.com/ignitionrobotics/ign-gazebo/pull/1411)
* [Pull request #1430](https://github.com/ignitionrobotics/ign-gazebo/pull/1430)

1. Fix segfault at exit
* [Pull request #1317](https://github.com/ignitionrobotics/ign-gazebo/pull/1317)

1. Add Gaussian noise to Odometry Publisher
* [Pull request #1393](https://github.com/ignitionrobotics/ign-gazebo/pull/1393)

### Ignition Gazebo 6.8.0 (2022-04-04)

1. ServerConfig accepts an sdf::Root DOM object
Expand Down
10 changes: 10 additions & 0 deletions examples/standalone/comms/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR)

project(ign-gazebo-comms)

find_package(ignition-transport12 QUIET REQUIRED)
set(IGN_TRANSPORT_VER ${ignition-transport12_VERSION_MAJOR})

add_executable(publisher publisher.cc)
target_link_libraries(publisher
ignition-transport${IGN_TRANSPORT_VER}::core)
106 changes: 106 additions & 0 deletions examples/standalone/comms/publisher.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,106 @@
/*
* Copyright (C) 2022 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.
*
*/

// Example: ./publisher addr2

#include <atomic>
#include <chrono>
#include <csignal>
#include <iostream>
#include <string>
#include <thread>

#include <ignition/msgs.hh>
#include <ignition/transport.hh>

/// \brief Flag used to break the publisher loop and terminate the program.
static std::atomic<bool> g_terminatePub(false);

//////////////////////////////////////////////////
/// \brief Usage function.
void usage()
{
std::cerr << "./publisher <dst_address>" << std::endl;
}

//////////////////////////////////////////////////
/// \brief Function callback executed when a SIGINT or SIGTERM signals are
/// captured. This is used to break the infinite loop that publishes messages
/// and exit the program smoothly.
void signal_handler(int _signal)
{
if (_signal == SIGINT || _signal == SIGTERM)
g_terminatePub = true;
}

//////////////////////////////////////////////////
int main(int argc, char **argv)
{
if (argc != 2)
{
usage();
return -1;
}

// Install a signal handler for SIGINT and SIGTERM.
std::signal(SIGINT, signal_handler);
std::signal(SIGTERM, signal_handler);

// Create a transport node and advertise a topic.
ignition::transport::Node node;
std::string topic = "/broker/msgs";

auto pub = node.Advertise<ignition::msgs::Dataframe>(topic);
if (!pub)
{
std::cerr << "Error advertising topic [" << topic << "]" << std::endl;
return -1;
}

std::this_thread::sleep_for(std::chrono::milliseconds(100));

// Prepare the message.
ignition::msgs::Dataframe msg;
msg.set_src_address("addr1");
msg.set_dst_address(argv[1]);

// Publish messages at 1Hz.
int counter = 0;
while (!g_terminatePub)
{
// Prepare the payload.
ignition::msgs::StringMsg payload;
payload.set_data("hello world " + std::to_string(counter));
std::string serializedData;
if (!payload.SerializeToString(&serializedData))
{
std::cerr << "Error serializing message\n"
<< payload.DebugString() << std::endl;
}
msg.set_data(serializedData);

if (!pub.Publish(msg))
break;

++counter;

std::cout << "Publishing hello on topic [" << topic << "]" << std::endl;
std::this_thread::sleep_for(std::chrono::milliseconds(1000));
}

return 0;
}
4 changes: 2 additions & 2 deletions examples/standalone/gtest_setup/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,8 @@ cmake_minimum_required(VERSION 3.11.0 FATAL_ERROR)
project(GTestSetup)

# Find Gazebo
set(IGN_GAZEBO_VER 7)
find_package(ignition-gazebo${IGN_GAZEBO_VER} REQUIRED)
find_package(ignition-gazebo7 REQUIRED)
set(IGN_GAZEBO_VER ${ignition-gazebo7_VERSION_MAJOR})

# Fetch and configure GTest
include(FetchContent)
Expand Down
177 changes: 177 additions & 0 deletions examples/worlds/perfect_comms.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,177 @@
<?xml version="1.0" ?>
<!--
Ignition Gazebo perfect-comms plugin demo.
Compile the comms publisher:
cd ign-gazebo/examples/standalone/comms
mkdir build
cd build
cmake ..
make
Try launching a comms subscriber:
ign topic -e -t addr2/rx
Try launching a comms publisher:
./publisher addr2
-->
<sdf version="1.6">
<world name="perfect_comms">

<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-user-commands-system"
name="ignition::gazebo::systems::UserCommands">
</plugin>
<plugin
filename="ignition-gazebo-scene-broadcaster-system"
name="ignition::gazebo::systems::SceneBroadcaster">
</plugin>
<plugin
filename="ignition-gazebo-perfect-comms-system"
name="ignition::gazebo::systems::PerfectComms">
</plugin>

<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
<diffuse>1 1 1 1</diffuse>
<specular>0.5 0.5 0.5 1</specular>
<attenuation>
<range>1000</range>
<constant>0.9</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<direction>-0.5 0.1 -0.9</direction>
</light>

<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</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="box1">
<pose>2 0 0.5 0 0 0</pose>
<link name="box_link">
<inertial>
<inertia>
<ixx>0.16666</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.16666</iyy>
<iyz>0</iyz>
<izz>0.16666</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>

<plugin
filename="ignition-gazebo-comms-endpoint-system"
name="ignition::gazebo::systems::CommsEndpoint">
<address>addr1</address>
<topic>addr1/rx</topic>
</plugin>
</model>

<model name="box2">
<pose>-2 0 0.5 0 0 0</pose>
<link name="box_link">
<inertial>
<inertia>
<ixx>0.16666</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.16666</iyy>
<iyz>0</iyz>
<izz>0.16666</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>0 0 1 1</ambient>
<diffuse>0 0 1 1</diffuse>
<specular>0 0 1 1</specular>
</material>
</visual>
</link>

<plugin
filename="ignition-gazebo-comms-endpoint-system"
name="ignition::gazebo::systems::CommsEndpoint">
<address>addr2</address>
<topic>addr2/rx</topic>
<broker>
<bind_service>/broker/bind</bind_service>
<unbind_service>/broker/unbind</unbind_service>
</broker>
</plugin>

</model>

</world>
</sdf>
Loading

0 comments on commit 7063d41

Please sign in to comment.