From 916fd01a5aa47f98b9a99d1befe43434a57ca27b Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Wed, 31 Mar 2021 09:29:27 -0700 Subject: [PATCH 1/5] =?UTF-8?q?=F0=9F=8E=88=207.0.0=20(#150)?= 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 | 7 ++++--- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 12373ec0..2bd625ef 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -14,7 +14,7 @@ find_package(ignition-cmake2 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 604c5014..0d572c35 100644 --- a/Changelog.md +++ b/Changelog.md @@ -2,7 +2,7 @@ ### Ignition Msgs 7.x.x (2021-xx-xx) -### Ignition Msgs 7.0.0 (2021-xx-xx) +### Ignition Msgs 7.0.0 (2021-03-30) 1. Master branch updates * [Pull request #141](https://github.com/ignitionrobotics/ign-msgs/pull/141) @@ -21,6 +21,7 @@ 1. README updates for Edifice * [Pull request #125](https://github.com/ignitionrobotics/ign-msgs/pull/125) + * [Pull request #148](https://github.com/ignitionrobotics/ign-msgs/pull/148) 1. Added render order to material msgs * [Pull request #118](https://github.com/ignitionrobotics/ign-msgs/pull/118) @@ -119,11 +120,11 @@ ### 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 2ecd38cba50cb9fb2cc6f469c8eedec3d5d03fef Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Mon, 5 Apr 2021 09:19:42 -0700 Subject: [PATCH 2/5] Added particle_emitter vector message (#149) Signed-off-by: Nate Koenig Co-authored-by: Nate Koenig --- proto/ignition/msgs/particle_emitter_v.proto | 37 ++++++++++++++++++++ 1 file changed, 37 insertions(+) create mode 100644 proto/ignition/msgs/particle_emitter_v.proto diff --git a/proto/ignition/msgs/particle_emitter_v.proto b/proto/ignition/msgs/particle_emitter_v.proto new file mode 100644 index 00000000..b4d91ebc --- /dev/null +++ b/proto/ignition/msgs/particle_emitter_v.proto @@ -0,0 +1,37 @@ +/* + * 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. + * +*/ + +syntax = "proto3"; +package ignition.msgs; +option java_package = "com.ignition.msgs"; +option java_outer_classname = "ParticleEmitterVProtos"; + +/// \ingroup ignition.msgs +/// \interface ParticleEmitterV +/// \brief Message for a list of particle emitters. + +import "ignition/msgs/header.proto"; +import "ignition/msgs/particle_emitter.proto"; + +message ParticleEmitter_V +{ + /// \brief Optional header data. + Header header = 1; + + /// \brief List of particle emitters. + repeated ParticleEmitter particle_emitter = 2; +} From acf45d4b2a4416f38b1850561cc0e6f031baf021 Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Tue, 6 Apr 2021 12:07:45 -0700 Subject: [PATCH 3/5] Prepare for 6.5.0 release (#154) Signed-off-by: Nate Koenig Co-authored-by: Nate Koenig --- CMakeLists.txt | 2 +- Changelog.md | 7 +++++-- 2 files changed, 6 insertions(+), 3 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 0a19ff4c..4e70c46d 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-msgs6 VERSION 6.4.0) +project(ignition-msgs6 VERSION 6.5.0) #============================================================================ # Find ignition-cmake diff --git a/Changelog.md b/Changelog.md index 8770bf38..8d897802 100644 --- a/Changelog.md +++ b/Changelog.md @@ -1,8 +1,11 @@ ## Ignition Msgs 6.x -### Ignition Msgs 6.x.x (2021-xx-xx) +### Ignition Msgs 6.5.0 (2021-04-06) -### Ignition Msgs 6.3.0 (2021-03-01) +1. Added particle_emitter vector message + * [Pull request 149](https://github.com/ignitionrobotics/ign-msgs/pull/149) + +### Ignition Msgs 6.4.0 (2021-03-01) 1. Support 'has' functionality in particle Emitter. * [Pull request 137](https://github.com/ignitionrobotics/ign-msgs/pull/137) From 77593c2ceb5135a0991ff09f32f91ce7bd02f2ba Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Fri, 30 Apr 2021 13:46:50 -0700 Subject: [PATCH 4/5] =?UTF-8?q?=F0=9F=8E=88=207.1.0=20(#158)?= 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 | 5 +++++ 2 files changed, 6 insertions(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 3f156e82..09e22447 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.0.0) +project(ignition-msgs7 VERSION 7.1.0) #============================================================================ # Find ignition-cmake diff --git a/Changelog.md b/Changelog.md index 62a0db71..030e3999 100644 --- a/Changelog.md +++ b/Changelog.md @@ -2,6 +2,11 @@ ### Ignition Msgs 7.x.x (2021-xx-xx) +### Ignition Msgs 7.1.0 (2021-04-30) + +1. Added particle_emitter vector message + * [Pull request #149](https://github.com/ignitionrobotics/ign-msgs/pull/149) + ### Ignition Msgs 7.0.0 (2021-03-30) 1. Master branch updates From 3d8d8281deb002691db5891fb06d654640027369 Mon Sep 17 00:00:00 2001 From: Adwait Date: Mon, 10 May 2021 16:28:24 +0530 Subject: [PATCH 5/5] fixed the width spelling in the comment (#161) Signed-off-by: addy1997 --- proto/ignition/msgs/image.proto | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/proto/ignition/msgs/image.proto b/proto/ignition/msgs/image.proto index 5a793465..cabf218b 100644 --- a/proto/ignition/msgs/image.proto +++ b/proto/ignition/msgs/image.proto @@ -56,7 +56,7 @@ message Image /// \brief Optional header data Header header = 1; - /// \brief Image wisth (number of columns) + /// \brief Image width (number of columns) uint32 width = 2; /// \brief Image height (number of rows)