From c0af1471bb915ee32c0ec6cb95688dcaefc131b9 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Mon, 15 Mar 2021 17:00:47 -0500 Subject: [PATCH 1/2] Add ignition version of nav_msgs/OccupancyGrid (#138) (#143) Signed-off-by: Michael Carroll --- proto/ignition/msgs/occupancy_grid.proto | 66 ++++++++++++++++++++++++ 1 file changed, 66 insertions(+) create mode 100644 proto/ignition/msgs/occupancy_grid.proto diff --git a/proto/ignition/msgs/occupancy_grid.proto b/proto/ignition/msgs/occupancy_grid.proto new file mode 100644 index 00000000..4685a127 --- /dev/null +++ b/proto/ignition/msgs/occupancy_grid.proto @@ -0,0 +1,66 @@ +/* + * 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 = "OccpuancyGridProtos"; + +/// \ingroup ignition.msgs +/// \interface OccupancyGrid +/// \brief This message is designed to mimic ROS nav_msgs/OccupancyGrid to +/// facilitate transfer/conversion of data between Ignition and ROS. +/// +/// See: http://docs.ros.org/melodic/api/nav_msgs/html/msg/OccupancyGrid.html + +import "ignition/msgs/header.proto"; +import "ignition/msgs/pose.proto"; +import "ignition/msgs/time.proto"; + + +message OccupancyGrid +{ + message MapMetaInfo + { + /// \brief The map load time + Time map_load_time = 1; + + /// \brief The map resolution (meters/cell) + double resolution = 2; + + /// \brief The map width (cells) + uint32 width = 3; + + /// \brief The map height (cells) + uint32 height = 4; + + /// \brief The origin of the map. This is the real-world pose of the + /// cell (0,0) in the map + Pose origin = 5; + }; + + /// \brief Optional header data. This should contain time of map validity + /// and the coordinate frame ID. + Header header = 1; + + /// \brief Metadata for the map. + MapMetaInfo info = 2; + + /// \brief The map data, in row-major order, starting with (0,0). + /// Occupancy probabilities are in the range [0,100]. Unknown is -1. + bytes data = 3; +}; From f000899723315e88bfd6c891a96483623451a202 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Wed, 17 Mar 2021 11:18:59 -0500 Subject: [PATCH 2/2] Prepare for 5.7.0 (#144) Signed-off-by: Michael Carroll --- CMakeLists.txt | 2 +- Changelog.md | 12 ++++++++++++ 2 files changed, 13 insertions(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index fbda45c3..d77976a0 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.6.0) +project(ignition-msgs5 VERSION 5.7.0) #============================================================================ # Find ignition-cmake diff --git a/Changelog.md b/Changelog.md index a2b03fcc..cc024274 100644 --- a/Changelog.md +++ b/Changelog.md @@ -3,6 +3,18 @@ ### Ignition Msgs 5.X.X (20XX-XX-XX) +### Ignition Msgs 5.7.0 (2021-03-17) + +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 + * [Pull request 141](https://github.com/ignitionrobotics/ign-msgs/pull/141) + +1. Add windows installation; move installation in README to tutorial + * [Pull request 126](https://github.com/ignitionrobotics/ign-msgs/pull/126) + ### Ignition Msgs 5.6.0 (2020-12-28) 1. Add JointTrajectory message.