From 934f58428e48cdf022453519d4b75549f45ef53d Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Mon, 9 Aug 2021 10:35:59 -0700 Subject: [PATCH 1/7] =?UTF-8?q?=F0=9F=8E=88=205.8.0=20(#173)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Louise Poubel --- CMakeLists.txt | 2 +- Changelog.md | 14 ++++++++++++-- 2 files changed, 13 insertions(+), 3 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index d2cae5ee..25c69814 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -3,7 +3,7 @@ cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR) #============================================================================ # Initialize the project #============================================================================ -project(ignition-msgs5 VERSION 5.7.0) +project(ignition-msgs5 VERSION 5.8.0) #============================================================================ # Find ignition-cmake diff --git a/Changelog.md b/Changelog.md index cc024274..80626d51 100644 --- a/Changelog.md +++ b/Changelog.md @@ -2,14 +2,24 @@ ### Ignition Msgs 5.X.X (20XX-XX-XX) +### Ignition Msgs 5.8.0 (2021-08-06) + +1. Adds PerformanceSensorMetrics proto message. + * [Pull request #172](https://github.com/ignitionrobotics/ign-msgs/pull/172) + +1. Detect ign instead of using cmake module to check for ignition-tools + * [Pull request #166](https://github.com/ignitionrobotics/ign-msgs/pull/166) + +1. Remove tools/code_check and update codecov + * [Pull request #164](https://github.com/ignitionrobotics/ign-msgs/pull/164) ### Ignition Msgs 5.7.0 (2021-03-17) -1. Add ignition version of nav_msgs/OccupancyGrid (backport #138) +1. Add ignition version of nav_msgs/OccupancyGrid (backport #138) * [Pull request 143](https://github.com/ignitionrobotics/ign-msgs/pull/143) * [Pull request 143](https://github.com/ignitionrobotics/ign-msgs/pull/138) -1. Master branch updates +1. Master branch updates * [Pull request 141](https://github.com/ignitionrobotics/ign-msgs/pull/141) 1. Add windows installation; move installation in README to tutorial From 2f2d86edbcbeec3e66a553608787f5792858c76e Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Fri, 10 Sep 2021 16:07:54 -0700 Subject: [PATCH 2/7] =?UTF-8?q?=F0=9F=8E=88=207.2.0=20(#181)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Louise Poubel --- CMakeLists.txt | 2 +- Changelog.md | 17 ++++++++++++++++- 2 files changed, 17 insertions(+), 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 6302dbe8..52b8acbb 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -3,7 +3,7 @@ cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR) #============================================================================ # Initialize the project #============================================================================ -project(ignition-msgs7 VERSION 7.1.0) +project(ignition-msgs7 VERSION 7.2.0) #============================================================================ # Find ignition-cmake diff --git a/Changelog.md b/Changelog.md index 89e74ed5..4852887f 100644 --- a/Changelog.md +++ b/Changelog.md @@ -1,6 +1,21 @@ ## Ignition Msgs 7.x -### Ignition Msgs 7.x.x (2021-xx-xx) +### Ignition Msgs 7.2.0 (2021-09-10) + +1. Adds PerformanceSensorMetrics proto message. + * [Pull request #172](https://github.com/ignitionrobotics/ign-msgs/pull/172) + +1. Detect ign instead of using cmake module to check for ignition-tools + * [Pull request #166](https://github.com/ignitionrobotics/ign-msgs/pull/166) + +1. Bazel build support + * [Pull request #95](https://github.com/ignitionrobotics/ign-msgs/pull/95) + +1. Remove tools/code_check and update codecov + * [Pull request #164](https://github.com/ignitionrobotics/ign-msgs/pull/164) + +1. Fixed the width spelling in a comment + * [Pull request #161](https://github.com/ignitionrobotics/ign-msgs/pull/161) ### Ignition Msgs 7.1.0 (2021-04-30) From bf0db74a9f17897e4a0ed42768aa522e7dfcc26b Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Thu, 23 Sep 2021 13:40:53 -0700 Subject: [PATCH 3/7] =?UTF-8?q?=F0=9F=A5=B3=20Update=20ign-tools=20issue?= =?UTF-8?q?=20on=20README=20(#184)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Louise Poubel --- README.md | 19 ++----------------- 1 file changed, 2 insertions(+), 17 deletions(-) diff --git a/README.md b/README.md index 2bb7e772..b84dd92d 100644 --- a/README.md +++ b/README.md @@ -26,27 +26,12 @@ See the [installation tutorial](https://ignitionrobotics.org/api/msgs/6.2/index. In the event that the installation is a mix of Debian and from source, command line tools from `ign-tools` may not work correctly. -A workaround for a single package is to define the environment variable +A workaround is to define the environment variable `IGN_CONFIG_PATH` to point to the location of the Ignition library installation, where the YAML file for the package is found, such as ``` export IGN_CONFIG_PATH=/usr/local/share/ignition ``` -However, that environment variable only takes a single path, which means if the -installations from source are in different locations, only one can be specified. - -Another workaround for working with multiple Ignition libraries on the command -line is using symbolic links to each library's YAML file. -``` -mkdir ~/.ignition/tools/configs -p -cd ~/.ignition/tools/configs/ -ln -s /usr/local/share/ignition/fuel4.yaml . -ln -s /usr/local/share/ignition/transport8.yaml . -ln -s /usr/local/share/ignition/transportlog8.yaml . -... -export IGN_CONFIG_PATH=$HOME/.ignition/tools/configs -``` - -This issue is tracked [here](https://github.com/ignitionrobotics/ign-tools/issues/8). +This issue is tracked [here](https://github.com/ignitionrobotics/ign-tools/issues/61). From e050940eba6b3be89b933b3edd7f84446fb2b447 Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Tue, 28 Sep 2021 10:26:35 -0700 Subject: [PATCH 4/7] =?UTF-8?q?=F0=9F=8E=88=208.0.0=20(#186)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Louise Poubel --- CMakeLists.txt | 2 +- Changelog.md | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index d7910719..3509ffb7 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -14,7 +14,7 @@ find_package(ignition-cmake2 2.8.0 REQUIRED) #============================================================================ # Configure the project #============================================================================ -ign_configure_project(VERSION_SUFFIX pre1) +ign_configure_project(VERSION_SUFFIX) #============================================================================ # Set project-specific options diff --git a/Changelog.md b/Changelog.md index 9f3d9d0a..8c872e29 100644 --- a/Changelog.md +++ b/Changelog.md @@ -1,6 +1,6 @@ ## Ignition Msgs 8.x -### Ignition Msgs 8.0.0 (2021-09-xx) +### Ignition Msgs 8.0.0 (2021-09-27) 1. scene.proto: add shadow_caster_material_name * [Pull request #179](https://github.com/ignitionrobotics/ign-msgs/pull/179) From 7199bfb1b372f11b387d6b4d1e22a897c49622cc Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Thu, 14 Oct 2021 09:15:50 -0700 Subject: [PATCH 5/7] Support colcon in windows CI (#189) * README: update windows jenkins job name * Remove unneeded configure.bat script Signed-off-by: Steve Peters --- README.md | 2 +- configure.bat | 25 ------------------------- 2 files changed, 1 insertion(+), 26 deletions(-) delete mode 100644 configure.bat diff --git a/README.md b/README.md index db86b828..9afb4c81 100644 --- a/README.md +++ b/README.md @@ -12,7 +12,7 @@ Build | Status Test coverage | [![codecov](https://codecov.io/gh/ignitionrobotics/ign-msgs/branch/main/graph/badge.svg)](https://codecov.io/gh/ignitionrobotics/ign-msgs) Ubuntu Bionic | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_msgs-ci-main-bionic-amd64)](https://build.osrfoundation.org/job/ignition_msgs-ci-main-bionic-amd64) Homebrew | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_msgs-ci-main-homebrew-amd64)](https://build.osrfoundation.org/job/ignition_msgs-ci-main-homebrew-amd64) -Windows | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_msgs-ci-main-windows7-amd64)](https://build.osrfoundation.org/job/ignition_msgs-ci-main-windows7-amd64) +Windows | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ign_msgs-ci-win)](https://build.osrfoundation.org/job/ign_msgs-ci-win) Ignition Messages is a component in the [Ignition](http://ignitionrobotics.org) framework, a set of libraries designed to rapidly develop robot applications. diff --git a/configure.bat b/configure.bat deleted file mode 100644 index b178f6af..00000000 --- a/configure.bat +++ /dev/null @@ -1,25 +0,0 @@ - -:: NOTE: This script is only meant to be used as part of the ignition developers' CI system -:: Users and developers should build and install this library using cmake and Visual Studio - - -:: Install dependencies -call %win_lib% :download_unzip_install protobuf-3.4.1-vc15-x64-dll-MD.zip -call %win_lib% :install_ign_project ign-math ign-math6 - -:: Set configuration variables -@set build_type=Release -@if not "%1"=="" set build_type=%1 -@echo Configuring for build type %build_type% - -:: Go to the directory that this configure.bat file exists in -cd /d %~dp0 - -:: Create a build directory and configure -md build -cd build -cmake .. -G "NMake Makefiles" -DCMAKE_INSTALL_PREFIX="%WORKSPACE_INSTALL_DIR%" -DCMAKE_BUILD_TYPE="%build_type%" -DBUILD_TESTING:BOOL=False -:: Note: We disable testing by default. If the intention is for the CI to build and test -:: this project, then the CI script will turn it back on. - -:: If the caller wants to build and/or install, they should do so after calling this script From a89c15d510d14a02377ca7729ac06cced7547831 Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Mon, 18 Oct 2021 11:34:28 -0700 Subject: [PATCH 6/7] Fix trivial typo in command line help message (#191) * Fix trivial typo in command line help message Signed-off-by: Nate Koenig * Remove comment Signed-off-by: Nate Koenig Co-authored-by: Nate Koenig --- src/cmd/cmdmsgs.rb.in | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/cmd/cmdmsgs.rb.in b/src/cmd/cmdmsgs.rb.in index 4659a6af..5bd150a9 100644 --- a/src/cmd/cmdmsgs.rb.in +++ b/src/cmd/cmdmsgs.rb.in @@ -38,9 +38,9 @@ COMMANDS = { 'msg' => "Print information about ignition messages.\n\n" + " ign msg [options]\n\n" + "Options:\n\n" + - " -i [ --info ] arg " + + " -i [ --info ] arg " + "Get info about the specified message type.\n" + - " -l [ --list ] List all topics.\n" + + " -l [ --list ] List all message types.\n" + COMMON_OPTIONS } @@ -60,7 +60,7 @@ class Cmd opt_parser = OptionParser.new do |opts| opts.banner = usage - opts.on('-h', '--help", "Print this help message') do + opts.on('-h', '--help', 'Print this help message') do puts usage exit(0) end From c6eaf2deab8f1ec2d7d6a65df2c5daa04d5f5bea Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Thu, 21 Oct 2021 14:27:10 -0700 Subject: [PATCH 7/7] Fix pre1 Signed-off-by: Nate Koenig --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index b9098d3b..ff0a240b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -14,7 +14,7 @@ find_package(ignition-cmake2 2.8.0 REQUIRED) #============================================================================ # Configure the project #============================================================================ -ign_configure_project(VERSION_SUFFIX) +ign_configure_project(VERSION_SUFFIX pre1) #============================================================================ # Set project-specific options