Skip to content

Commit

Permalink
Fixing review comments
Browse files Browse the repository at this point in the history
* Rename mapio -> map_io
* Move all OccGridLoader functionality into MapServer. Remove OccGridLoader
* Switch all thresholds to be floating-point
* Switch loadMapFromYaml() returning type to LOAD_MAP_STATUS and remove
  duplicating code from loadMapResponseFromYaml()
* Make mapCallback() to be lambda-function
* Make saveMapCallback() to be class method
* Utilize local rclcpp_node_ from LifecycleNode instead of map_listener_.
  Remove map_listener_ and got_map_msg_ variables.
* Rename load_map_callback() -> loadMapCallback() and make it to be class method
* Rename handle_occ_callback() -> getMapCallback() and make it to be class method
* Force saveMapTopicToFile() and saveMapToFile() to work with constant arguments
* map_saver_cli: move arguments parsing code into new parse_arguments() function
* Rename test_occ_grid_node -> test_map_server_node and fix test
* Rename test_occ_grid -> test_occ_grid and fix test
* Fix copyrights
* Fix comments
* Update README
  • Loading branch information
AlexeyMerzlyakov committed Apr 22, 2020
1 parent 8256121 commit 89ece96
Show file tree
Hide file tree
Showing 20 changed files with 532 additions and 741 deletions.
23 changes: 11 additions & 12 deletions nav2_map_server/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -34,20 +34,19 @@ add_executable(${map_saver_cli_executable}
add_executable(${map_saver_server_executable}
src/map_saver_server_main.cpp)

set(mapio_library_name mapio)
set(map_io_library_name map_io)

set(library_name ${map_server_executable}_core)

add_library(${mapio_library_name} SHARED
add_library(${map_io_library_name} SHARED
src/map_mode.cpp
src/mapio.cpp)
src/map_io.cpp)

add_library(${library_name} SHARED
src/occ_grid_loader.cpp
src/map_server.cpp
src/map_saver.cpp)

set(mapio_dependencies
set(map_io_dependencies
yaml_cpp_vendor
nav_msgs
nav2_util
Expand Down Expand Up @@ -80,11 +79,11 @@ ament_target_dependencies(${map_saver_server_executable}
ament_target_dependencies(${library_name}
${map_server_dependencies})

ament_target_dependencies(${mapio_library_name}
${mapio_dependencies})
ament_target_dependencies(${map_io_library_name}
${map_io_dependencies})

target_link_libraries(${library_name}
${mapio_library_name})
${map_io_library_name})

target_link_libraries(${map_server_executable}
${library_name})
Expand All @@ -95,13 +94,13 @@ target_link_libraries(${map_saver_cli_executable}
target_link_libraries(${map_saver_server_executable}
${library_name})

target_include_directories(${mapio_library_name} SYSTEM PRIVATE
target_include_directories(${map_io_library_name} SYSTEM PRIVATE
${GRAPHICSMAGICKCPP_INCLUDE_DIRS})

target_link_libraries(${mapio_library_name}
target_link_libraries(${map_io_library_name}
${GRAPHICSMAGICKCPP_LIBRARIES})

install(TARGETS ${map_server_executable} ${library_name} ${mapio_library_name}
install(TARGETS ${map_server_executable} ${library_name} ${map_io_library_name}
${map_saver_cli_executable} ${map_saver_server_executable}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
Expand All @@ -125,6 +124,6 @@ endif()
ament_export_include_directories(include)
ament_export_libraries(
${library_name}
${mapio_library_name}
${map_io_library_name}
)
ament_package()
21 changes: 8 additions & 13 deletions nav2_map_server/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -21,25 +21,20 @@ Currently map server divides into tree parts:

- `map_server`
- `map_saver`
- `mapio` library
- `map_io` library

`map_server` is responsible for loading the map from a file through command-line interface
or by using serice requests. The main concept is to have `MapLoader` abstract base class
and type-specific map loaders which derive from this class. There is currently one such
derived class, the `OccGridLoader`, which converts an input image to an OccupancyGrid and
makes this available via topic and service interfaces. The `MapServer` class is a ROS2 node
that uses the appropriate loader, based on an input parameter.
or by using serice requests.

`map_saver` saves the map into a file. Like `map_server`, it has an ability to save the map from
command-line or by calling a service.

`mapio` - is a map input-output library. The library is designed to be an object-independent
`map_io` - is a map input-output library. The library is designed to be an object-independent
in order to allow easily save/load map from external code just by calling necessary function.
This library is also used by `map_loader` and `map_saver` to work. Currently it contains
OccupancyGrid saving/loading functions moved from the rest part of map server code.
Like `OccGridLoader`, it also designed to be replaceble for a new IO library
(e.g. for library with new map encoding method or any other library supporting costmaps,
multifloor maps, etc...).
It is designed to be replaceble for a new IO library (e.g. for library with new map encoding
method or any other library supporting costmaps, multifloor maps, etc...).

### CLI-usage

Expand Down Expand Up @@ -116,11 +111,11 @@ $ ros2 run nav2_map_server map_saver_cli [arguments] [--ros-args ROS remapping a

## Currently Supported Map Types

- Occupancy grid (nav_msgs/msg/OccupancyGrid), via the OccGridLoader
- Occupancy grid (nav_msgs/msg/OccupancyGrid)

## MapIO library

`MapIO` library contains following API functions declared in `mapio.hpp` to work with
`MapIO` library contains following API functions declared in `map_io.hpp` to work with
OccupancyGrid maps:

- loadMapYaml(): Load and parse the given YAML file
Expand All @@ -144,6 +139,6 @@ Service usage examples:

```
$ ros2 service call /map_server/load_map nav2_msgs/srv/LoadMap "{map_url: /ros/maps/map.yaml}"
$ ros2 service call /map_saver/save_map nav2_msgs/srv/SaveMap "{map_topic: map, map_url: my_map, image_format: pgm, map_mode: trinary, free_thresh: 25, occupied_thresh: 65}"
$ ros2 service call /map_saver/save_map nav2_msgs/srv/SaveMap "{map_topic: map, map_url: my_map, image_format: pgm, map_mode: trinary, free_thresh: 0.25, occupied_thresh: 0.65}"
```

Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@
// Copyright (c) 2020 Samsung R&D Institute Russia
// Copyright (c) 2018 Intel Corporation
//
// Licensed under the Apache License, Version 2.0 (the "License");
Expand All @@ -15,8 +14,8 @@

/* OccupancyGrid map input-output library */

#ifndef NAV2_MAP_SERVER__MAPIO_HPP_
#define NAV2_MAP_SERVER__MAPIO_HPP_
#ifndef NAV2_MAP_SERVER__MAP_IO_HPP_
#define NAV2_MAP_SERVER__MAP_IO_HPP_

#include <string>
#include <vector>
Expand All @@ -40,6 +39,14 @@ struct LoadParameters
bool negate;
};

typedef enum
{
LOAD_MAP_SUCCESS,
MAP_DOES_NOT_EXIST,
INVALID_MAP_METADATA,
INVALID_MAP_DATA
} LOAD_MAP_STATUS;

/**
* @brief Load and parse the given YAML file
* @param yaml_filename Name of the map file passed though parameter
Expand All @@ -63,9 +70,9 @@ void loadMapFromFile(
* generate an OccupancyGrid
* @param yaml_file Name of input YAML file
* @param map Output loaded map
* @return true or false
* @return status of map loaded
*/
bool loadMapFromYaml(
LOAD_MAP_STATUS loadMapFromYaml(
const std::string & yaml_file,
nav_msgs::msg::OccupancyGrid & map);

Expand All @@ -76,22 +83,21 @@ struct SaveParameters
{
std::string map_file_name{""};
std::string image_format{""};
int free_thresh{0};
int occupied_thresh{0};
double free_thresh{0.0};
double occupied_thresh{0.0};
MapMode mode{MapMode::Trinary};
};

/**
* @brief Write OccupancyGrid map to file
* @param map OccupancyGrid map data
* @param save_parameters Map saving parameters.
* NOTE: save_parameters could be updated during function execution.
* @return true or false
*/
bool saveMapToFile(
const nav_msgs::msg::OccupancyGrid & map,
SaveParameters & save_parameters);
const SaveParameters & save_parameters);

} // namespace nav2_map_server

#endif // NAV2_MAP_SERVER__MAPIO_HPP_
#endif // NAV2_MAP_SERVER__MAP_IO_HPP_
65 changes: 45 additions & 20 deletions nav2_map_server/include/nav2_map_server/map_saver.hpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,4 @@
// Copyright (c) 2020 Samsung R&D Institute Russia
// Copyright (c) 2018 Intel Corporation
// Copyright (c) 2020 Samsung Research Russia
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -23,7 +22,7 @@
#include "nav2_util/lifecycle_node.hpp"
#include "nav2_msgs/srv/save_map.hpp"

#include "mapio.hpp"
#include "map_io.hpp"

namespace nav2_map_server
{
Expand All @@ -48,46 +47,72 @@ class MapSaver : public nav2_util::LifecycleNode
/**
* @brief Read a message from incoming map topic and save map to a file
* @param map_topic Incoming map topic name
* NOTE: map_topic could be updated during function execution.
* @param save_parameters Map saving parameters.
* NOTE: save_parameters could be updated during function execution.
* @return true of false
*/
bool saveMapTopicToFile(std::string & map_topic, SaveParameters & save_parameters);
bool saveMapTopicToFile(
const std::string & map_topic,
const SaveParameters & save_parameters);

protected:
// Lifecycle interfaces
/**
* @brief Sets up map saving service
* @param state Lifecycle Node's state
* @return Success or Failure
*/
nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override;
/**
* @brief Called when node switched to active state
* @param state Lifecycle Node's state
* @return Success or Failure
*/
nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override;
/**
* @brief Called when node switched to inactive state
* @param state Lifecycle Node's state
* @return Success or Failure
*/
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override;
/**
* @brief Called when it is required node clean-up
* @param state Lifecycle Node's state
* @return Success or Failure
*/
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override;
/**
* @brief Called when in Shutdown state
* @param state Lifecycle Node's state
* @return Success or Failure
*/
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
/**
* @brief Called when Error is raised
* @param state Lifecycle Node's state
* @return Success or Failure
*/
nav2_util::CallbackReturn on_error(const rclcpp_lifecycle::State & state) override;

/**
* @brief A callback function that receives map message from subscribed topic
* @param map Occupancy Grid message data
* @brief Map saving service callback
* @param request_header Service request header
* @param request Service request
* @param response Service response
*/
void mapCallback(const nav_msgs::msg::OccupancyGrid::SharedPtr msg);
void saveMapCallback(
const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<nav2_msgs::srv::SaveMap::Request> request,
std::shared_ptr<nav2_msgs::srv::SaveMap::Response> response);

// The timeout for saving the map in service
std::shared_ptr<rclcpp::Duration> save_map_timeout_;
// Default values for map thresholds
int free_thresh_default_;
int occupied_thresh_default_;
double free_thresh_default_;
double occupied_thresh_default_;

// The name of the service for saving a map from topic
const std::string save_map_service_name_{"save_map"};
// A service to save the map to a file at run time (SaveMap)
rclcpp::Service<nav2_msgs::srv::SaveMap>::SharedPtr save_map_service_;

// Map topic listener node
rclcpp::Node::SharedPtr map_listener_;

// Pointer to map message received in the subscription callback
nav_msgs::msg::OccupancyGrid::SharedPtr msg_;
// Indicator that map message was receiced
bool got_map_msg_;
};

} // namespace nav2_map_server
Expand Down
Loading

0 comments on commit 89ece96

Please sign in to comment.