ROS库-----grid_map介绍

GridMap是一个用于管理和存储二维网格地图的C++库,支持多层数据。它适用于移动机器人制图,可以存储如高程、方差、颜色等数据。该库支持高效地图重定位、基于Eigen的数据操作,并提供了多种辅助函数和迭代器来方便地访问单元格数据。

摘要生成于 C知道 ,由 DeepSeek-R1 满血版支持, 前往体验 >

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.
  • 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.

The grid map package has been tested with ROS Indigo, Jade (under Ubuntu 14.04) and Kinetic (under Ubuntu 16.04). 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
Maintainer: Péter Fankhauser, pfankhauser@ethz.ch
With contributions by: Martin Wermelinger, Philipp Krüsi, Remo Diethelm, Ralph Kaestner, Elena Stumm, Dominic Jud, Daniel Stonier, Christos Zalidis
Affiliation: Autonomous Systems Lab, ETH Zurich

Grid map example in RViz

Publications

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

  • 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é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-indigo-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 grid_map_cv package depends additionally on OpenCV.

The other packages depend additionally on the ROS standard installation (roscpp, tf, filters, sensor_msgs, nav_msgs, and cv_bridge).

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/ethz-asl/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_cv provides conversions of grid maps from and to OpenCV image types.
  • 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_visualization contains a node written to convert GridMap messages to other ROS message types for example for visualization in RViz.
  • grid_map_filters builds on the ROS filters package to process grid maps as a sequence of filters.
  • grid_map_demos contains several nodes for demonstration purposes.

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

  • 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
    

Conventions & Definitions

Grid map layers

Grid map conventions

Iterators

The grid map library contains various iterators for convenience.

Grid mapSubmapCircleLinePolygon
Grid map iteratorSubmap iteratorCircle iteratorLine iteratorPolygon iterator
EllipseSpiral   
Ellipse iteratorSpiral 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 grid map such that the corresponce between data and the map frame does not change. Data in the overlapping region before and after the position change remains stored. Data that falls outside of 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.
setPosition(...)move(...)
Grid map iteratorSubmap 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_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 cloudVectorsOccupancy gridGrid cells
Point cloudVectorsOccupancy gridGrid 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).

Build Status

Devel Job Status

 IndigoJadeKinetic
grid_mapBuild StatusBuild StatusBuild Status
docBuild StatusBuild StatusBuild Status

Release Job Status

 IndigoJadeKinetic
grid_mapBuild StatusBuild StatusBuild Status
grid_map_coreBuild StatusBuild StatusBuild Status
grid_map_rosBuild StatusBuild StatusBuild Status
grid_map_msgsBuild StatusBuild StatusBuild Status
grid_map_rviz_pluginBuild StatusBuild StatusBuild Status
grid_map_visualizationBuild StatusBuild StatusBuild Status
grid_map_filtersBuild StatusBuild StatusBuild Status
grid_map_loaderBuild StatusBuild StatusBuild Status
grid_map_demosBuild StatusBuild StatusBuild Status

Bugs & Feature Requests

Please report bugs and request features using the Issue Tracker.


原文链接:https://github.com/ethz-asl/grid_map/blob/master/README.md

<think>我们正在处理用户关于ROS Noetic中map_server包安装的问题。用户询问命令`sudo apt install ros-noetic-map-server`的作用以及如何在ROS Noetic中安装map_server包。 根据引用[1]和引用[3],我们可以知道`ros-noetic-map-server`是ROS Noetic版本中提供地图服务器功能的一个包。这个包允许ROS系统加载和保存地图(通常为occupancy grid map),并提供服务使得其他节点可以获取地图数据。 安装命令`sudo apt install ros-noetic-map-server`的作用是使用APT(Ubuntu的包管理工具)从ROS官方仓中下载并安装`ros-noetic-map-server`包及其依赖项。 在ROS中,通常推荐使用APT来安装官方提供的包,这样可以自动处理依赖关系。安装步骤一般如下: 1. 确保已经正确安装和配置了ROS Noetic环境(包括设置`/etc/apt/sources.list.d`中的ROS和`apt`密钥)。 2. 更新APT包索引:`sudo apt update` 3. 执行安装命令:`sudo apt install ros-noetic-map-server` 安装完成后,就可以在ROS中使用`map_server`节点了。该节点主要提供两个功能: - 作为地图服务器,通过ROS话题(`map`)发布地图数据。 - 提供`map_saver`命令行工具,用于将当前地图保存到文件。 用户可能还需要注意,根据引用[2],在安装某些ROS包时,可能需要使用`rosdep`来安装依赖。但是,由于`map_server`是ROS官方包,通过APT安装时会自动处理依赖,所以通常不需要手动运行`rosdep`。 此外,引用[3]提到了ROS包和系统Python包的区别,但`map_server`主要是C++编写的,所以不涉及Python包的问题。 因此,我们可以这样回答用户:</think>### ROS Noetic中`map_server`包的安装与作用 #### 命令作用解析 `sudo apt install ros-noetic-map-server` 是ROS Noetic中安装地图服务器功能包的核心命令,主要实现: 1. **核心功能安装** 提供`map_server`节点,用于加载/保存二维占据栅格地图(Occupancy Grid Map),支持`.pgm`和`.yaml`格式的地图文件[^1]。 2. **依赖项自动处理** 自动安装以下关键依赖: - `nav_msgs`(导航消息接口) - `sdl-image1.2`(图像解析- `tf2`(坐标变换系统) - `yaml-cpp`(YAML配置文件解析) 3. **ROS集成** 将二进制文件安装到ROS专属路径`/opt/ros/noetic`,确保与ROS构建系统(catkin)兼容[^3]。 #### 完整安装步骤 ```bash # 1. 更新软件源索引 sudo apt update # 2. 安装map_server核心包 sudo apt install ros-noetic-map-server # 3. 验证安装(需启动ROS环境) roscd map_server # 进入包目录 ls launch/ # 查看启动文件 ``` #### 功能验证方法 创建测试地图配置文件`test.yaml`: ```yaml image: test.pgm resolution: 0.05 origin: [0.0, 0.0, 0.0] negate: 0 occupied_thresh: 0.65 free_thresh: 0.196 ``` 启动服务节点: ```bash rosrun map_server map_server test.yaml ``` 成功启动后将发布`/map`话题(消息类型:`nav_msgs/OccupancyGrid`)。 #### 注意事项 1. **权限问题** 首次运行需添加执行权限:`chmod +x /opt/ros/noetic/lib/map_server/map_server` 2. **地图路径** 默认从`~/.ros/`读取地图文件,建议使用绝对路径指定地图位置 3. **依赖冲突** 如遇依赖错误,可通过修复命令解决: `rosdep install --from-paths src --ignore-src --rosdistro=noetic -y`[^2] ---
评论 1
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值