Code Monkey home page Code Monkey logo

grid_map's Introduction

Grid Map

Overview

This is a C++ library with ROS interface to manage two-dimensional grid maps with multiple data layers. It is designed for mobile robotic mapping to store data such as elevation, variance, color, friction coefficient, foothold quality, surface normal, traversability etc. It is used in the Robot-Centric Elevation Mapping package designed for rough terrain navigation.

Features:

  • Multi-layered: Developed for universal 2.5-dimensional grid mapping with support for any number of layers.
  • Efficient map re-positioning: Data storage is implemented as two-dimensional circular buffer. This allows for non-destructive shifting of the map's position (e.g. to follow the robot) without copying data in memory.
  • Based on Eigen: Grid map data is stored as Eigen data types. Users can apply available Eigen algorithms directly to the map data for versatile and efficient data manipulation.
  • Convenience functions: Several helper methods allow for convenient and memory safe cell data access. For example, iterator functions for rectangular, circular, polygonal regions and lines are implemented.
  • ROS interface: Grid maps can be directly converted to and from ROS message types such as PointCloud2, OccupancyGrid, GridCells, and our custom GridMap message. Conversion packages provide compatibility with costmap_2d, PCL, and OctoMap data types.
  • OpenCV interface: Grid maps can be seamlessly converted from and to OpenCV image types to make use of the tools provided by OpenCV.
  • Visualizations: The grid_map_rviz_plugin renders grid maps as 3d surface plots (height maps) in RViz. Additionally, the grid_map_visualization package helps to visualize grid maps as point clouds, occupancy grids, grid cells etc.
  • Filters: The grid_map_filters provides are range of filters to process grid maps as a sequence of filters. Parsing of mathematical expressions allows to flexibly setup powerful computations such as thresholding, normal vectors, smoothening, variance, inpainting, and matrix kernel convolutions.

This is research code, expect that it changes often and any fitness for a particular purpose is disclaimed.

The source code is released under a BSD 3-Clause license.

Author: Péter Fankhauser
Affiliation: ANYbotics
Maintainer: Maximilian Wulf, [email protected], Magnus Gärtner, [email protected]
With contributions by: Simone Arreghini, Tanja Baumann, Jeff Delmerico, Remo Diethelm, Perry Franklin, Magnus Gärtner, Ruben Grandia, Edo Jelavic, Dominic Jud, Ralph Kaestner, Philipp Krüsi, Alex Millane, Daniel Stonier, Elena Stumm, Martin Wermelinger, Christos Zalidis

This projected was initially developed at ETH Zurich (Autonomous Systems Lab & Robotic Systems Lab).

This work is conducted as part of ANYmal Research, a community to advance legged robotics.

Grid map example in RViz

Publications

If you use this work in an academic context, please cite the following publication:

P. Fankhauser and M. Hutter, "A Universal Grid Map Library: Implementation and Use Case for Rough Terrain Navigation", in Robot Operating System (ROS) – The Complete Reference (Volume 1), A. Koubaa (Ed.), Springer, 2016. (PDF)

@incollection{Fankhauser2016GridMapLibrary,
  author = {Fankhauser, P{\'{e}}ter and Hutter, Marco},
  booktitle = {Robot Operating System (ROS) – The Complete Reference (Volume 1)},
  title = {{A Universal Grid Map Library: Implementation and Use Case for Rough Terrain Navigation}},
  chapter = {5},
  editor = {Koubaa, Anis},
  publisher = {Springer},
  year = {2016},
  isbn = {978-3-319-26052-5},
  doi = {10.1007/978-3-319-26054-9{\_}5},
  url = {http://www.springer.com/de/book/9783319260525}
}

Documentation

An introduction to the grid map library including a tutorial is given in this book chapter.

The C++ API is documented here:

Installation

Installation from Packages

To install all packages from the grid map library as Debian packages use

sudo apt-get install ros-$ROS_DISTRO-grid-map

Building from Source

Dependencies

The grid_map_core package depends only on the linear algebra library Eigen.

sudo apt-get install libeigen3-dev

The other packages depend additionally on the ROS standard installation (roscpp, tf, filters, sensor_msgs, nav_msgs, and cv_bridge). Other format specific conversion packages (e.g. grid_map_cv, grid_map_pcl etc.) depend on packages described below in Packages Overview.

Building

To build from source, clone the latest version from this repository into your catkin workspace and compile the package using

cd catkin_ws/src
git clone https://github.com/anybotics/grid_map.git
cd ../
catkin_make

To maximize performance, make sure to build in Release mode. You can specify the build type by setting

catkin_make -DCMAKE_BUILD_TYPE=Release

Packages Overview

This repository consists of following packages:

  • grid_map is the meta-package for the grid map library.
  • grid_map_core implements the algorithms of the grid map library. It provides the GridMap class and several helper classes such as the iterators. This package is implemented without ROS dependencies.
  • grid_map_ros is the main package for ROS dependent projects using the grid map library. It provides the interfaces to convert grid maps from and to several ROS message types.
  • grid_map_demos contains several nodes for demonstration purposes.
  • grid_map_filters builds on the ROS Filters package to process grid maps as a sequence of filters.
  • grid_map_msgs holds the ROS message and service definitions around the [grid_map_msg/GridMap] message type.
  • grid_map_rviz_plugin is an RViz plugin to visualize grid maps as 3d surface plots (height maps).
  • grid_map_sdf provides an algorithm to convert an elevation map into a 3D signed distance field.
  • grid_map_visualization contains a node written to convert GridMap messages to other ROS message types for example for visualization in RViz.

Additional conversion packages:

  • grid_map_costmap_2d provides conversions of grid maps from costmap_2d map types.
  • grid_map_cv provides conversions of grid maps from and to OpenCV image types.
  • grid_map_octomap provides conversions of grid maps from OctoMap (OctoMap) maps.
  • grid_map_pcl provides conversions of grid maps from Point Cloud Library (PCL) polygon meshes and point clouds. For details, see the grid map pcl package README.

Unit Tests

Run the unit tests with

catkin_make run_tests_grid_map_core run_tests_grid_map_ros

or

catkin build grid_map --no-deps --verbose --catkin-make-args run_tests

if you are using catkin tools.

Usage

Demonstrations

The grid_map_demos package contains several demonstration nodes. Use this code to verify your installation of the grid map packages and to get you started with your own usage of the library.

  • simple_demo demonstrates a simple example for using the grid map library. This ROS node creates a grid map, adds data to it, and publishes it. To see the result in RViz, execute the command

      roslaunch grid_map_demos simple_demo.launch
    
  • tutorial_demo is an extended demonstration of the library's functionalities. Launch the tutorial_demo with

      roslaunch grid_map_demos tutorial_demo.launch
    
  • iterators_demo showcases the usage of the grid map iterators. Launch it with

      roslaunch grid_map_demos iterators_demo.launch
    
  • image_to_gridmap_demo demonstrates how to convert data from an image to a grid map. Start the demonstration with

      roslaunch grid_map_demos image_to_gridmap_demo.launch
    

    Image to grid map demo result

  • grid_map_to_image_demo demonstrates how to save a grid map layer to an image. Start the demonstration with

      rosrun grid_map_demos grid_map_to_image_demo _grid_map_topic:=/grid_map _file:=/home/$USER/Desktop/grid_map_image.png
    
  • opencv_demo demonstrates map manipulations with help of OpenCV functions. Start the demonstration with

      roslaunch grid_map_demos opencv_demo.launch
    

    OpenCV demo result

  • resolution_change_demo shows how the resolution of a grid map can be changed with help of the OpenCV image scaling methods. The see the results, use

      roslaunch grid_map_demos resolution_change_demo.launch
    
  • filters_demo uses a chain of ROS Filters to process a grid map. Starting from the elevation of a terrain map, the demo uses several filters to show how to compute surface normals, use inpainting to fill holes, smoothen/blur the map, and use math expressions to detect edges, compute roughness and traversability. The filter chain setup is configured in the filters_demo_filter_chain.yaml file. Launch the demo with

      roslaunch grid_map_demos filters_demo.launch
    

    Filters demo results

For more information about grid map filters, see grid_map_filters.

  • interpolation_demo shows the result of different interpolation methods on the resulting surface. The start the demo, use

      roslaunch grid_map_demos interpolation_demo.launch
    

The user can play with different worlds (surfaces) and different interpolation settings in the interpolation_demo.yaml file. The visualization displays the ground truth in green and yellow color. The interpolation result is shown in red and purple colors. Also, the demo computes maximal and average interpolation errors, as well as the average time required for a single interpolation query.

Grid map features four different interpolation methods (in order of increasing accuracy and increasing complexity):

  • NN - Nearest Neighbour (fastest, but least accurate).
  • Linear - Linear interpolation.
  • Cubic convolution - Piecewise cubic interpolation. Implemented using the cubic convolution algorithm.
  • Cubic - Cubic interpolation (slowest, but most accurate).

For more details check the literature listed in CubicInterpolation.hpp file.

Conventions & Definitions

Grid map layers

Grid map conventions

Iterators

The grid map library contains various iterators for convenience.

Grid map Submap Circle Line Polygon
Grid map iterator Submap iterator Circle iterator Line iterator Polygon iterator
Ellipse Spiral
Ellipse iterator Spiral iterator

Using the iterator in a for loop is common. For example, iterate over the entire grid map with the GridMapIterator with

for (grid_map::GridMapIterator iterator(map); !iterator.isPastEnd(); ++iterator) {
    cout << "The value at index " << (*iterator).transpose() << " is " << map.at("layer", *iterator) << endl;
}

The other grid map iterators follow the same form. You can find more examples on how to use the different iterators in the iterators_demo node.

Note: For maximum efficiency when using iterators, it is recommended to locally store direct access to the data layers of the grid map with grid_map::Matrix& data = map["layer"] outside the for loop:

grid_map::Matrix& data = map["layer"];
for (GridMapIterator iterator(map); !iterator.isPastEnd(); ++iterator) {
    const Index index(*iterator);
    cout << "The value at index " << index.transpose() << " is " << data(index(0), index(1)) << endl;
}

You can find a benchmarking of the performance of the iterators in the iterator_benchmark node of the grid_map_demos package which can be run with

rosrun grid_map_demos iterator_benchmark

Beware that while iterators are convenient, it is often the cleanest and most efficient to make use of the built-in Eigen methods. Here are some examples:

  • Setting a constant value to all cells of a layer:

      map["layer"].setConstant(3.0);
    
  • Adding two layers:

      map["sum"] = map["layer_1"] + map["layer_2"];
    
  • Scaling a layer:

      map["layer"] = 2.0 * map["layer"];
    
  • Max. values between two layers:

      map["max"] = map["layer_1"].cwiseMax(map["layer_2"]);
    
  • Compute the root mean squared error:

      map.add("error", (map.get("layer_1") - map.get("layer_2")).cwiseAbs());
      unsigned int nCells = map.getSize().prod();
      double rootMeanSquaredError = sqrt((map["error"].array().pow(2).sum()) / nCells);
    

Changing the Position of the Map

There are two different methods to change the position of the map:

  • setPosition(...): Changes the position of the map without changing data stored in the map. This changes the corresponce between the data and the map frame.

  • move(...): Relocates the region captured by grid map w.r.t. to the static grid map frame. Use this to move the grid map boundaries without relocating the grid map data. Takes care of all the data handling, such that the grid map data is stationary in the grid map frame.

    • Data in the overlapping region before and after the position change remains stored.
    • Data that falls outside the map at its new position is discarded.
    • Cells that cover previously unknown regions are emptied (set to nan). The data storage is implemented as two-dimensional circular buffer to minimize computational effort.

    Note: Due to the circular buffer structure, neighbouring indices might not fall close in the map frame. This assumption only holds for indices obtained by getUnwrappedIndex().

    setPosition(...) move(...)
    Grid map iterator Submap iterator

Packages

grid_map_rviz_plugin

This RViz plugin visualizes a grid map layer as 3d surface plot (height map). A separate layer can be chosen as layer for the color information.

Grid map visualization in RViz

grid_map_sdf

This package provides an efficient algorithm to convert an elevation map into a dense 3D signed distance field. Each point in the 3D grid contains the distance to the closest point in the map together with the gradient.

ANYmal SDF demo

grid_map_visualization

This node subscribes to a topic of type grid_map_msgs/GridMap and publishes messages that can be visualized in RViz. The published topics of the visualizer can be fully configure with a YAML parameter file. Any number of visualizations with different parameters can be added. An example is here for the configuration file of the tutorial_demo.

Point cloud Vectors Occupancy grid Grid cells
Point cloud Vectors Occupancy grid Grid cells

Parameters

  • grid_map_topic (string, default: "/grid_map")

    The name of the grid map topic to be visualized. See below for the description of the visualizers.

Subscribed Topics

Published Topics

The published topics are configured with the YAML parameter file. Possible topics are:

  • point_cloud (sensor_msgs/PointCloud2)

    Shows the grid map as a point cloud. Select which layer to transform as points with the layer parameter.

      name: elevation
      type: point_cloud
      params:
       layer: elevation
       flat: false # optional
    
  • flat_point_cloud (sensor_msgs/PointCloud2)

    Shows the grid map as a "flat" point cloud, i.e. with all points at the same height z. This is convenient to visualize 2d maps or images (or even video streams) in RViz with help of its Color Transformer. The parameter height determines the desired z-position of the flat point cloud.

      name: flat_grid
      type: flat_point_cloud
      params:
       height: 0.0
    

    Note: In order to omit points in the flat point cloud from empty/invalid cells, specify the layers which should be checked for validity with setBasicLayers(...).

  • vectors (visualization_msgs/Marker)

    Visualizes vector data of the grid map as visual markers. Specify the layers which hold the x-, y-, and z-components of the vectors with the layer_prefix parameter. The parameter position_layer defines the layer to be used as start point of the vectors.

      name: surface_normals
      type: vectors
      params:
       layer_prefix: normal_
       position_layer: elevation
       scale: 0.06
       line_width: 0.005
       color: 15600153 # red
    
  • occupancy_grid (nav_msgs/OccupancyGrid)

    Visualizes a layer of the grid map as occupancy grid. Specify the layer to be visualized with the layer parameter, and the upper and lower bound with data_min and data_max.

      name: traversability_grid
      type: occupancy_grid
      params:
       layer: traversability
       data_min: -0.15
       data_max: 0.15
    
  • grid_cells (nav_msgs/GridCells)

    Visualizes a layer of the grid map as grid cells. Specify the layer to be visualized with the layer parameter, and the upper and lower bounds with lower_threshold and upper_threshold.

      name: elevation_cells
      type: grid_cells
      params:
       layer: elevation
       lower_threshold: -0.08 # optional, default: -inf
       upper_threshold: 0.08 # optional, default: inf
    
  • region (visualization_msgs/Marker)

    Shows the boundary of the grid map.

      name: map_region
      type: map_region
      params:
       color: 3289650
       line_width: 0.003
    

Note: Color values are in RGB form as concatenated integers (for each channel value 0-255). The values can be generated like this as an example for the color green (red: 0, green: 255, blue: 0).

grid_map_filters

The grid_map_filters package containts several filters which can be applied a grid map to perform computations on the data in the layers. The grid map filters are based on ROS Filters, which means that a chain of filters can be configured as a YAML file. Furthermore, additional filters can be written and made available through the ROS plugin mechanism, such as the InpaintFilter from the grid_map_cv package.

Several basic filters are provided in the grid_map_filters package:

  • gridMapFilters/ThresholdFilter

    Set values in the output layer to a specified value if the condition_layer is exceeding either the upper or lower threshold (only one threshold at a time).

      name: lower_threshold
      type: gridMapFilters/ThresholdFilter
      params:
        condition_layer: layer_name
        output_layer: layer_name
        lower_threshold: 0.0 # alternative: upper_threshold
        set_to: 0.0 # # Other uses: .nan, .inf
    
  • gridMapFilters/MeanInRadiusFilter

    Compute for each cell of a layer the mean value inside a radius.

      name: mean_in_radius
      type: gridMapFilters/MeanInRadiusFilter
      params:
        input_layer: input
        output_layer: output
        radius: 0.06 # in m.
    
  • gridMapFilters/MedianFillFilter

    Compute for each NaN cell of a layer the median (of finites) inside a patch with radius. Optionally, apply median calculations for values that are already finite, the patch radius for these points is given by existing_value_radius. Note that the fill computation is only performed if the fill_mask is valid for that point.

      name: median
      type: gridMapFilters/MedianFillFilter
      params:
        input_layer: input
        output_layer: output
        fill_hole_radius: 0.11 # in m. 
        filter_existing_values: false # Default is false. If enabled it also does a median computation for existing values. 
        existing_value_radius: 0.2 # in m. Note that this option only has an effect if filter_existing_values is set true. 
        fill_mask_layer: fill_mask # A layer that is used to compute which areas to fill. If not present in the input it is automatically computed. 
        debug: false # If enabled, the additional debug_infill_mask_layer is published. 
        debug_infill_mask_layer: infill_mask # Layer used to visualize the intermediate, sparse-outlier removed fill mask. Only published if debug is enabled.
    
  • gridMapFilters/NormalVectorsFilter

    Compute the normal vectors of a layer in a map.

      name: surface_normals
      type: gridMapFilters/NormalVectorsFilter
      params:
        input_layer: input
        output_layers_prefix: normal_vectors_
        radius: 0.05
        normal_vector_positive_axis: z
    
  • gridMapFilters/NormalColorMapFilter

    Compute a new color layer based on normal vectors layers.

      name: surface_normals
      type: gridMapFilters/NormalColorMapFilter
      params:
        input_layers_prefix: normal_vectors_
        output_layer: normal_color
    
  • gridMapFilters/MathExpressionFilter

    Parse and evaluate a mathematical matrix expression with layers of a grid map. See EigenLab for the documentation of the expressions.

      name: math_expression
      type: gridMapFilters/MathExpressionFilter
      params:
        output_layer: output
        expression: acos(normal_vectors_z) # Slope.
        # expression: abs(elevation - elevation_smooth) # Surface roughness.
        # expression: 0.5 * (1.0 - (slope / 0.6)) + 0.5 * (1.0 - (roughness / 0.1)) # Weighted and normalized sum.
    
  • gridMapFilters/SlidingWindowMathExpressionFilter

    Parse and evaluate a mathematical matrix expression within a sliding window on a layer of a grid map. See EigenLab for the documentation of the expressions.

      name: math_expression
      type: gridMapFilters/SlidingWindowMathExpressionFilter
      params:
        input_layer: input
        output_layer: output
        expression: meanOfFinites(input) # Box blur
        # expression: sqrt(sumOfFinites(square(input - meanOfFinites(input))) ./ numberOfFinites(input)) # Standard deviation
        # expression: 'sumOfFinites([0,-1,0;-1,5,-1;0,-1,0].*elevation_inpainted)' # Sharpen with kernel matrix
        compute_empty_cells: true
        edge_handling: crop # options: inside, crop, empty, mean
        window_size: 5 # in number of cells (optional, default: 3), make sure to make this compatible with the kernel matrix
        # window_length: 0.05 # instead of window_size, in m
    
  • gridMapFilters/DuplicationFilter

    Duplicate a layer of a grid map.

      name: duplicate
      type: gridMapFilters/DuplicationFilter
      params:
        input_layer: input
        output_layer: output
    
  • gridMapFilters/DeletionFilter

    Delete layers from a grid map.

      name: delete
      type: gridMapFilters/DeletionFilter
      params:
        layers: [color, score] # List of layers.
    

Additionally, the grid_map_cv package provides the following filters:

  • gridMapCv/InpaintFilter

    Use OpenCV to inpaint/fill holes in a layer.

      name: inpaint
      type: gridMapCv/InpaintFilter
      params:
        input_layer: input
        output_layer: output
        radius: 0.05 # in m
    

Build Status

Devel Job Status

Kinetic Melodic Noetic
grid_map Build Status Build Status Build Status
doc Build Status Build Status Build Status

Release Job Status

Kinetic Melodic Noetic
grid_map Build Status Build Status Build Status
grid_map_core Build Status Build Status Build Status
grid_map_costmap_2d Build Status Build Status Build Status
grid_map_cv Build Status Build Status Build Status
grid_map_demos Build Status Build Status Build Status
grid_map_filters Build Status Build Status Build Status
grid_map_loader Build Status Build Status Build Status
grid_map_msgs Build Status Build Status Build Status
grid_map_octomap Build Status Build Status Build Status
grid_map_pcl Build Status Build Status Build Status
grid_map_ros Build Status Build Status Build Status
grid_map_rviz_plugin Build Status Build Status Build Status
grid_map_sdf Build Status Build Status Build Status
grid_map_visualization Build Status Build Status Build Status

Bugs & Feature Requests

Please report bugs and request features using the Issue Tracker.

grid_map's People

Contributors

alexmillane avatar aravindev avatar czalidis avatar djud avatar elenastumm avatar fabianje avatar fvina-anybotics avatar hogabrie avatar jeffdelmerico avatar jelavice avatar kralf avatar kruesip avatar marco-tranzatto avatar marcosuetterlin avatar martiwer avatar maximilianwulf avatar mgaertneratanybotics avatar mktk1117 avatar pfankhauser avatar pierrefranklin avatar pleemann avatar prajishkumar avatar remod avatar rubengrandia avatar samuelba avatar stonier avatar todorangrg avatar wsascha avatar yoshuanavaanybotics avatar yvaind avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

grid_map's Issues

addLayerFromImage broken (?) for cv::Mat images of float type

I tried converting a floating point cv::Mat to a layer and noted that the grid map ends up having extremely small entries (magniture ~E-37). The cv image however has entries in the range [0, 31.0]. Investigating I found the following line: https://github.com/ethz-asl/grid_map/blob/master/grid_map_cv/include/grid_map_cv/GridMapCvConverter.hpp#L96
Setting the max by casting to (float)std::numeric_limits<Type_>::max(); works for small integer types, but not if Type is a float (or double).

I'll do my own small conversion for the moment, but two action items might be useful:

  • Document that float images are not really supported by the function
  • Possibly add a converter that can directly convert float cv::Mat to GridMap without scaling the entries

missing config folder in grid_map_demos

the config folder from grid_map_demos is not present in the indigo .deb:

roslaunch grid_map_demos tutorial_demo.launch

error loading tag:
file does not exist [/opt/ros/indigo/share/grid_map_demos/config/tutorial_demo.yaml]
XML is
The traceback for the exception was written to the log file

Provide a catkin-free cmake file

As grid_map core does not need ROS I would add a custom Cmake file without catkin references for those who don't need ROS and don't have it installed.

Compilation Error in Indigo 1.11.20

When I run catkin_make, I got following:

ExpressionFilter.cpp:56:88: error: no matching function for call to ‘grid_map::SlidingWindowMathExpressionFilter<grid_map::GridMap>::getParam(std::string, bool&)’
if (!FilterBase<T>::getParam(std::string("compute_empty_cells"), isComputeEmptyCells_)) {
                                                                                        ^
/home/cutcat/catkin_ws_hujun/src/grid_map/grid_map_filters/src/SlidingWindowMathExpressionFilter.cpp:56:88: note: candidates are:
In file included from /home/cutcat/catkin_ws_hujun/src/grid_map/grid_map_filters/include/grid_map_filters/SlidingWindowMathExpressionFilter.hpp:15:0,
                 from /home/cutcat/catkin_ws_hujun/src/grid_map/grid_map_filters/src/SlidingWindowMathExpressionFilter.cpp:9:
opt/ros/indigo/include/filters/filter_base.h:121:8: note: bool filters::FilterBase<T>::getParam(const string&, std::string&) [with T = grid_map::GridMap; std::string = std::basic_string<char>]
   bool getParam(const std::string& name, std::string& value)
...

My ros version is Indigo 1.11.20.
It seems like the filter_base.h file in Indigo 1.11.20 have no override function for getParam(string&, bool ).
Also I found filter_base.h has getParam(string&, bool ) in Indigo 1.11.21 on my friend's computer, so should I build this pakage in higher Indigo version like 1.11.21?

Index use inconsistent between toCvImage(..) and addLayerFromImage(..)

In toCvImage the order of the index access (1,0) into the cv::Mat (code) is exactly in opposite order to access in addLayerFromImage (0,1) (code).

This means that when creating a cv::Mat from a grid map layer, performing some operations on it and then adding it back as another layer using both conversion methods mentioned above, the new layer will be rotated by 90 degrees. Looks like a bug to me, or is there some kind of rationale for this?

GridMap iterator col-major order or row-major order ?

I am using the 1.4.1 version (apt-get install of ubuntu packages).

I run the iterator_demo, the iterator goes in column-major order, however the gif image of this github repo shows that the iterator goes in row-major order.

I am confused and want to ask that which one is correct ?

GridMap and CostMap messages

Moving the discussion here from email so there will be a visible, relevant history.

Proposal : find a way to have GridMap and CostMap objects use the same message object.

PolygonIterator getting stuck

Hi, I can't 100% reproduce this bug, but it seems to me that if one (or more?) of the vertices of the polygon used for the PolygonIterator is outside of the map, for some reason my code just hangs.

It does not happen all the time when I have a polygon that's not fully inside the map, but it happens a lot, and if i reexecute some scenario that got stuck it always gets stuck again.

Anyone else ever experienced something like this?

Compilation Error

While compiling grid_map_rviz_plugin master branch on Ubuntu 14 with a bunch of compilation flag set I got the following compilation error :

grid_map_rviz_plugin/src/GridMapVisual.cpp:73:18: error: suggest parentheses around '&&' within '||' [-Werror=parentheses]

Building local grid map with stereo camera

hello guys, I want to build my own grid map on ROS Indigo with a sensor (e.g. kinect or Realsense camera) but without using a robot and navigation, just building the local grid map that should represent the obstacles detected by the sensor. What should I do with this grid map library? Do I need to work with the node "elevation mapping" in addition? Thanks!

Conversion from CostMap2D to GridMap

Standard ROS navigation uses CostMap2D as a cost map representation and when implementing a nav_core::BaseGlobalPlanner plugin that uses grid_map as a back-end, it would be desirable to have a converter that allows initalizing the internal grid_map from a CostMap2D.
Are there any plans for implementing this (or even some implementation out there that I missed)?

New indigo/kinetic releases?

Getting ready to release the cost map counterparts to this library and just realised the debs aren't up to date with the api I'm making use of here in the master branch.

@pfankhauser any chance you can bump a new release on these?

No possibility to `resize` a GridMap ?

Hi,
I started using the grid_map_core pkg recently aiming at incrementally building a GridMap. However it seems there are no possibility to resize 'on the fly' a GridMap (resize while preserving the existing data).
The setGeometry functions internally call clearAll thus aren't suited for incremental building. I came across both addDataFrom & extendToInclude functions which both require as input argument another GridMap which is a bit of an overshoot - instantiation of a second GridMap object, internal copy of the current object etc...
Did I miss something or is it a missing functionality ??

grid_map doesn't transform according to pose in message

As far as I can tell grid_map cannot transform according to the z value or orientation in GridMapInfo.msg

We have our own heightmapping tool which creates a grid relative to a frame.
grid_map_alignment
... note that the large grid in the 'director' UI is not aligned with the heightmap grid. also note that the gridmap is aligned with the robot's orientation, by design.

I suppose the solution would be to add our frame to TF and set the x,y values to zero. But I wanted to ask why a full 3d pose is included in the ROS message but not used?

Is GridMap rviz rendering one cell short ?

Not sure if it is actually an issue but when overlaying an occupancy grid and a grid map, the two plots mismatch - see attached screenshot. Visually it looks like grid map is one cell short.
I noticed that in the GridMapVisual class cells are iterated up to rows\cols -1.

Is this the intended behavior ? What is the rational behind this ?

screenshot from 2017-10-15 15-56-42

Simple 50x50 square fully marked as occupied. The occupancy grid overflow on each side (black border). Moreover, the grid map displayed is only 49x49.

screenshot from 2017-10-15 15-59-16

Grid Map RViz Plugin: Alpha Channel

Only other grid_map's can be seen if a grid_map is set to transparent (alpha<1). Robot model and other markers are not visible through transparent grid_map's.

grid_map_rviz_issue_1
grid_map_rviz_issue_2

[grid_map_cv] Conversion to OpenCV force NaN to 0

When converting a GridMap to an OpenCV image with the method grid_map:GridMapCvConverter::toImage, the cv::Mat is initialized with zeros (black pixels) (here) then, only finite values are copied from the GridMap to the cv::Mat (here).

In other words the NaN values are automatically translated into black pixels.

For my use case (processing a map during a SLAM), I have a lot of NaN values and I need that information in OpenCV.
So maybe, setting the value of the pixels to the mid value between lowerValue and upperValue is more interesting than forcing to 0 by default.

iterator_demo throws exception

When running the iterator demo, the program terminates after a while with the following message:

$ roslaunch grid_map_demos iterators_demo.launch
# ...
[ INFO] [1472111866.193859810]: Running polygon iterator demo.
terminate called after throwing an instance of 'std::runtime_error'
  what():  Time is out of dual 32-bit range

Moving Costmap2DConverter.hpp breaks downstream packages

The recent moving of the include file: ethz-asl@787747e in #96 is breaking downstream packages expecting the header.

A backwards compatibility header with a deprecation warning would be appreciated.

http://build.ros.org/view/Ibin_uT64/job/Ibin_uT64__cost_map_ros__ubuntu_trusty_amd64__binary/8/console

00:07:47.321 /tmp/binarydeb/ros-indigo-cost-map-ros-0.3.1/src/lib/converter.cpp:23:47: fatal error: grid_map_ros/Costmap2DConverter.hpp: No such file or directory
00:07:47.321  #include <grid_map_ros/Costmap2DConverter.hpp>
00:07:47.321    

Alignment issues with Eigen datatypes and vectorization

Hi there,
first of all, thanks for this easy-to-use and well documented library!

There however seem to be alignment issues with the Eigen datatypes when compiling the library and software including its headers, which can lead to segmentation faults with compiling with vectorization (SSE) enabled. This probably is the case as you use Eigen datatypes like Eigen::Vector2d as a member of a structs/classes or in stl containers, like here:
https://github.com/ethz-asl/grid_map/blob/master/grid_map_core/include/grid_map_core/Polygon.hpp#L206

See https://eigen.tuxfamily.org/dox-devel/group__DenseMatrixManipulation__Alignement.html for more information on the particular issues.

As far as I can see:

  • best would be to adapt the code to use the Eigen allocators with correct alignment for vectorization
  • second best to use Eigen::DontAlign datatypes to prevent alignment issues
  • third best to at least warn the user to turn off Eigen vectorization as otherwise it can lead to hard-to-debug segmentation faults
    (see Eigen docs linked above for details on each of the three options)

Release with metapackage

I find the ROS wiki package documentation quite useful when learning about new code. So far only grid_map had a page and so I have started adding empty wiki pages for the other packages as well, e.g. http://wiki.ros.org/grid_map_core).

Now, each package looks quite lonely, since there is no stack/metapackage linking them. Hence, I like to suggest adding a metapackage, which links to all grid_map packages. Doing so will enable the ROS wiki to link between the packages via a stack page. This page is also well suited to be a landing page from which one can point to the other important packages.

Also installing the metapackage will automatically pull in the other packages.

An example is the rocon metapackage and the related wiki page (notice the list of packages below the release buttons).

origin conflict when converting from grid map to occupancy grid

I started playing around with this library and as a first test I implemented a "round trip conversion": nav_msgs::OccupancyGrid-> grid_map_msgs::GridMap -> grid_map::GridMap -> nav_msgs::OccupancyGrid.

The first conversion is done by my own implementation (couldn't find an implementation in this library), the second is using grid_map::GridMapRosConverter::fromMessage and the last grid_map::GridMapRosConverter::toOccupancyGrid.

The result looks fine, except 1) the costmap is rotated and 2) there is an offset in the origin's position.

Starting with the first issue, the original origin's quaternion is:

    orientation: 
      x: 0.0
      y: 0.0
      z: 0.0
      w: 1.0

The quaternion of the intermediate grid map is the same:

    orientation: 
      x: 0.0
      y: 0.0
      z: 0.0
      w: 1.0

But the final quaternion is different:

    orientation: 
      x: 0.0
      y: 0.0
      z: 1.0
      w: 0.0

Looking at the code, I found this part:

occupancyGrid.info.origin.orientation.x = 0.0;
occupancyGrid.info.origin.orientation.y = 0.0;
occupancyGrid.info.origin.orientation.z = 1.0;  // yes, this is correct.
occupancyGrid.info.origin.orientation.w = 0.0;

I don't understand why this change is necessary. Could someone please explain?

Looking at the second issue about the position offset the situation is similar. The original origin position in my example is:

    position: 
      x: -50.0
      y: -50.0
      z: 0.0

The position of the grid map's origin is the same. But during the conversion into a occupancy grid the origin is shifted/adjusted to:

    position: 
      x: 7.45058059692e-07
      y: 7.45058059692e-07
      z: 0.0

The reference frame for the origin of the occupancy grid in ROS (e.g. when published by move_base) seems to be one of the corners. When looking into the [conversion code (part 1, part 2) it seems to be assumed that the reference frame is the centre. What's the reason behind this?

CRTP Base XyzMap Class

Like #51, another idea to bring closer together the GridMap and CostMap implementations.

I was thinking of a CRTP class, much like Eigen does for it's matrices.

This would have several advantages:

  • Move alot of geometry/structural related code that is common to both into the base class.
  • Define templatised virtuals in the base class that XxxMap implementations require.
  • Child implementations can exist without being template classes themselves

The third advantage is good. I'm not really thinking about providing support for a variety of child implementations (that starts to go down the road of YAGNI), however it does make it easier for my colleagues to dive into building/maintaining the CostMap class if it itself isn't a massively templatised (or specialisation of a template) itself.

I'd like to have a crack at this one before #51 as it covers a significantly larger amound of overlap than the messages do.

LineIterator has potential bug?

I've been using grid_map for a while. I found LineIterator occasionally crash if I initialize it with two 'Position's, and access the grid map with

LineIterator iter(*grid_map_, pos1, pos2);
for (; !iter.isPastEnd(); ++iter)
{
  grid_map_->at("map", *iter) = foo;
}

This is most likely when both 'pos1' and 'pos2' are out of valid range.

I looked into the source code of 'LineIterator' and found that the constructor will NOT initialize anything if 'getIndexLimitedToMapRange()' returns false. In this case, when you invoke 'isPastEnd()', it'll probably return false because it actually returns 'iCell_ > nCells_'. NOTE the 'iCell_' and 'nCells_' were not initialized properly.

changeResolution cause segfault with wrong startIndex

I think there's a bug with GridMapCvProcessing.

If I have a map of fixed area at high resolution (say, 4 x 4 meters, 1 cm) and I want the same area at low resolution (say 4 x 4 meters, 4 cm) by applying the changeResolution method, this line causes segfault if the starting index of the original map at high resolution is out of bounds of the target map.

The new starting index should be somehow scaled as well, to find the closest cell to the original in the low resolution map.

README.md line 127: description typo

Line 127:
for (grid_map::GridMapIterator iterator(map); !iterator.isPassedEnd(); ++iterator) {

should be:
for (grid_map::GridMapIterator iterator(map); !iterator.isPastEnd(); ++iterator) {

Selection feature with RViz plugin

Have you'll considered adding the "Select" feature to the RViz plugin for users to be able to click on a GridMap cell and get it local & global coordinates. It would also be great to get the list of layer values for the selected grid cell. I, personally, do not have much experience writing RViz plugins so was wondering if this a planned feature or if you have thoughts on how easy/ hard it would be to implement something like this. Thanks!

resize() with initial value?

Regarding to GridMap::add(const std::string& layer, const double value), we can add layers with initial value. However, GridMap::resize(const Eigen::Array2i& size) only resize all layers without filling any data.

If I want to extend all layers with their initial value, is there any way to do that?

Thanks.

access normals from gridmap variable

I have a question: from the RViz I can see that the gridmap is visualized with some sort of normal to orient the cell/mesh. This means that for each cell a normal is computed. Is it available from the gridmap object or it is computed by the RViz plugin from the neighbors?

Is there a method to get the normals automatically?

Submap has different size than given in parameters provided to getSubmap()

I've been running into a problem with maps not matching up that I suspect could be related to mismatching sizes. So what I have is the following: A static_map_ containing standard occupancy data that is fixed wrt to world. I also have a "moving" elevation map local_elevation_map_. I want to fuse the local elevation data to static_map_, adding obstacles based on elevation data.

To this end, I do the following:

  const grid_map::Length& local_length = local_elevation_map_.getLength();
  const grid_map::Position& local_position = local_elevation_map_.getPosition();

  static_map_.extendToInclude(local_elevation_map_);

  bool submap_create_success;
  grid_map::GridMap static_cut = this->static_map_.getSubmap(local_position, local_length, submap_create_success);

  grid_map::Matrix& elev_data   = local_elevation_map_["elevation"];
  grid_map::Matrix& static_cut_data = static_cut["occupancy"];

  for (grid_map::GridMapIterator iterator(local_elevation_map_); !iterator.isPastEnd(); ++iterator) {
      const grid_map::Index index(*iterator);

      // According to some rule, add obstacle information to the map
      if ( std::abs( robot_elevation - elev_data(index(0), index(1)) ) > 0.38 ){
         static_cut_data(index(0), index(1)) = 100.0;
      }
  }
  static_map_.addDataFrom(static_cut, true, true, true);

So essentially, my goal was to create a subMap with exactly the same size and origin as the local elevation map and then iterate over/compare them using the same index. This works in the sense that I get data out, but it looks transformed incorrectly (i.e. obstacles in the elevation map show up in a different place in the static_map_ when visualizing them). With some debugging I found that the length of my local_elevation_map_ is 6, but that of the generated submap static_cut is 6.05. Now I can see how this can happen due to discretization, but it's highly inconvenient :)

I thus have a request and a question:

It would probably be good to indicate in documentation that the actual size of the returned submap might be different from what was requested. Alternatively, if possible it could be made to actually always have the requested size, but I think this might be tricky due to the discrete nature.

What would be the "proper" way of doing what I want (add data from a local map to a world fixed one based on some rule)?

Failing unit tests under ROS Jade.

[----------] 2 tests from checkGetCentroid
[ RUN      ] checkGetCentroid.triangle
/home/peter/jade_ws/src/grid_map/grid_map_core/test/PolygonTest.cpp:33: Failure
Value of: centroid.x()
  Actual: 0.83333333333333326
Expected: expectedCentroid.x()
Which is: 0.5
[  FAILED  ] checkGetCentroid.triangle (0 ms)
[ RUN      ] checkGetCentroid.rectangle
/home/peter/jade_ws/src/grid_map/grid_map_core/test/PolygonTest.cpp:47: Failure
Value of: centroid.x()
  Actual: -0.4907407407407407
Expected: expectedCentroid.x()
Which is: -0.5
[  FAILED  ] checkGetCentroid.rectangle (0 ms)

Eigen Plugins Order

Currently, there's an error when Eigen is not loaded at first from grid_map_core because of the Eigen Plugins.

Iterating w/ speed in mind

In the iterators demo, the iteration is using a string key based lookup to the layers to pull data at every index, which can be slow if you're just wanting to do full iterations over the data.

My first take was just to pull the data matrices for the layers and iterate over them directly, however after understanding a bit better what is happening with the internal storage, I gather this is a bad idea since a move will have shifted your sense of where the start is in that data matrix.

So instead, I've taken to really using the grid map iterators to pull the indices and operate on the matrix directly as follows:

grid_map::Matrix& data_layer_one = my_grid_map.get("layer_one");
grid_map::Matrix& data_layer_two = my_grid_map.get("layer_two");
for (grid_map::GridMapIterator iterator(my_grid_map); !iterator.isPastEnd(); ++iterator) {
  int i = (*iterator)(0);
  int j = (*iterator)(1);
  // do something with data_layer_one(i, j);
  // do something with data_layer_two(i, j);
}

Is this the recommended way? If it is, it would be good to have that in the iterators demo to show how you might iterate over a grid map with speed.

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.