diff --git a/map_skeletonizer/.clang-format b/map_skeletonizer/.clang-format new file mode 100644 index 0000000..cdf4928 --- /dev/null +++ b/map_skeletonizer/.clang-format @@ -0,0 +1,6 @@ +BasedOnStyle: Google +UseTab: Never +ColumnLimit: 80 +AccessModifierOffset: -2 +AlignConsecutiveAssignments: true +AlignConsecutiveMacros: true diff --git a/map_skeletonizer/CMakeLists.txt b/map_skeletonizer/CMakeLists.txt new file mode 100644 index 0000000..30a4cc2 --- /dev/null +++ b/map_skeletonizer/CMakeLists.txt @@ -0,0 +1,211 @@ +cmake_minimum_required(VERSION 3.0.2) +project(map_skeletonizer) + +## Compile as C++11, supported in ROS Kinetic and newer +set(CMAKE_CXX_STANDARD 14) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED COMPONENTS + cad2cav_types + roscpp +) + +## System dependencies are found with CMake's conventions +find_package(Boost REQUIRED) +find_package(Eigen3 REQUIRED) + + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +## To declare and build messages, services or actions from within this +## package, follow these steps: +## * Let MSG_DEP_SET be the set of packages whose message types you use in +## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). +## * In the file package.xml: +## * add a build_depend tag for "message_generation" +## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET +## * If MSG_DEP_SET isn't empty the following dependency has been pulled in +## but can be declared for certainty nonetheless: +## * add a exec_depend tag for "message_runtime" +## * In this file (CMakeLists.txt): +## * add "message_generation" and every package in MSG_DEP_SET to +## find_package(catkin REQUIRED COMPONENTS ...) +## * add "message_runtime" and every package in MSG_DEP_SET to +## catkin_package(CATKIN_DEPENDS ...) +## * uncomment the add_*_files sections below as needed +## and list every .msg/.srv/.action file to be processed +## * uncomment the generate_messages entry below +## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) + +## Generate messages in the 'msg' folder +# add_message_files( +# FILES +# Message1.msg +# Message2.msg +# ) + +## Generate services in the 'srv' folder +# add_service_files( +# FILES +# Service1.srv +# Service2.srv +# ) + +## Generate actions in the 'action' folder +# add_action_files( +# FILES +# Action1.action +# Action2.action +# ) + +## Generate added messages and services with any dependencies listed here +# generate_messages( +# DEPENDENCIES +# std_msgs # Or other packages containing msgs +# ) + +################################################ +## Declare ROS dynamic reconfigure parameters ## +################################################ + +## To declare and build dynamic reconfigure parameters within this +## package, follow these steps: +## * In the file package.xml: +## * add a build_depend and a exec_depend tag for "dynamic_reconfigure" +## * In this file (CMakeLists.txt): +## * add "dynamic_reconfigure" to +## find_package(catkin REQUIRED COMPONENTS ...) +## * uncomment the "generate_dynamic_reconfigure_options" section below +## and list every .cfg file to be processed + +## Generate dynamic reconfigure parameters in the 'cfg' folder +# generate_dynamic_reconfigure_options( +# cfg/DynReconf1.cfg +# cfg/DynReconf2.cfg +# ) + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if your package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( + INCLUDE_DIRS include + LIBRARIES map_skeletonizer + CATKIN_DEPENDS cad2cav_types roscpp +# DEPENDS system_lib +) + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations +include_directories( + include + ${catkin_INCLUDE_DIRS} + ${Boost_INCLUDE_DIR} + ${EIGEN3_INCLUDE_DIR} +) + +## Declare a C++ library +add_library(${PROJECT_NAME} + src/distance_map.cpp +) + +## Add cmake target dependencies of the library +## as an example, code may need to be generated before libraries +## either from message generation or dynamic reconfigure +# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Declare a C++ executable +## With catkin_make all packages are built within a single CMake context +## The recommended prefix ensures that target names across packages don't collide +# add_executable(${PROJECT_NAME}_node src/map_skeletonizer_node.cpp) + +## Rename C++ executable without prefix +## The above recommended prefix causes long target names, the following renames the +## target back to the shorter version for ease of user use +## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" +# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") + +## Add cmake target dependencies of the executable +## same as for the library above +# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Specify libraries to link a library or executable target against +target_link_libraries(${PROJECT_NAME} + ${catkin_LIBRARIES} + ${Boost_LIBRARIES} +) + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# catkin_install_python(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables for installation +## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html +# install(TARGETS ${PROJECT_NAME}_node +# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark libraries for installation +## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html +install(TARGETS ${PROJECT_NAME} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} +) + +## Mark cpp header files for installation +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + FILES_MATCHING + PATTERN "*.h" + PATTERN "*.hpp" + PATTERN ".svn" EXCLUDE +) + +## Mark other files for installation (e.g. launch and bag files, etc.) +# install(FILES +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) + +############# +## Testing ## +############# + +## Add gtest based cpp test target and link libraries +# catkin_add_gtest(${PROJECT_NAME}-test test/test_map_skeletonizer.cpp) +# if(TARGET ${PROJECT_NAME}-test) +# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) +# endif() + +## Add folders to be run by python nosetests +# catkin_add_nosetests(test) diff --git a/map_skeletonizer/include/map_skeletonizer/distance_map.hpp b/map_skeletonizer/include/map_skeletonizer/distance_map.hpp new file mode 100644 index 0000000..2ce7cac --- /dev/null +++ b/map_skeletonizer/include/map_skeletonizer/distance_map.hpp @@ -0,0 +1,151 @@ +#ifndef __MAP_SKELETONIZER_DISTANCE_MAP_HPP__ +#define __MAP_SKELETONIZER_DISTANCE_MAP_HPP__ + +/** + * @file distance_map.hpp + * @author Zhihao Ruan (ruanzh@seas.upenn.edu) + * + * @brief Implements distance map update strategy in: + * B. Lau, C. Sprunk and W. Burgard, "Improved updating of Euclidean distance + * maps and Voronoi diagrams," IROS 2010. + * + * @date 2021-11-14 + */ + +#include +#include +#include +#include + +#include "cad2cav_types/types.hpp" + +namespace cad2cav { +namespace skeletonizer { + +struct CellAttribute { + Eigen::Vector2i obs_pos; // position of the closest obstacle in map + bool to_raise; + bool on_voronoi; + + CellAttribute() : obs_pos(-1, -1), to_raise(false), on_voronoi(false) {} +}; + +struct Cell { + // cell position in map + Eigen::Vector2i pos; + // distance to closest obstacle in map + double dist; + // may be the same attribute as in attrib_, or value-to-set + CellAttribute attrib; + + Cell() : pos(-1, -1), dist(std::numeric_limits::infinity()) {} + Cell(Eigen::Vector2i in_pos, double in_dist) : pos(in_pos), dist(in_dist) {} +}; + +bool operator>(const Cell& a, const Cell& b) { return a.dist > b.dist; } + +class DistanceMapBuilder { +public: + DistanceMapBuilder() : map_width_(-1), map_height_(-1) {} + DistanceMapBuilder(const nav_msgs::OccupancyGrid& occ_grid, + int8_t cell_occupied_threshold = 50); + /** + * @brief Gets the current distance map. Stored in row-major order. + * + * @return const std::vector& + */ + const std::vector& getDistanceMap() const noexcept { return dist_; } + /** + * @brief Gets the distance to closest obstacle of cell (x,y). + * + * @param x + * @param y + * @return double& + */ + double& distAt(int x, int y); + double& distAt(Eigen::Vector2i xy); + const double& distAt(int x, int y) const; + const double& distAt(Eigen::Vector2i xy) const; + /** + * @brief Gets the attribute of cell (x,y). + * + * @param x + * @param y + * @return CellAttribute& + */ + CellAttribute& attributeAt(int x, int y); + CellAttribute& attributeAt(Eigen::Vector2i xy); + const CellAttribute& attributeAt(int x, int y) const; + const CellAttribute& attributeAt(Eigen::Vector2i xy) const; + /** + * @brief Check if (x,y) is an obstacle. + * Only depends on whether attrib_[x,y].obs_pos == (x,y). + * + * @param x + * @param y + * @return true + * @return false + */ + bool isOccupied(int x, int y) const; + bool isOccupied(Eigen::Vector2i xy) const; + /** + * @brief Makes (x,y) as a new obstacle, and starts a new wave propagation. + * + * @param x + * @param y + * @return Cell + */ + Cell makeObstacle(int x, int y) const; + /** + * @brief Makes (x,y) as a free cell (unoccupied), and starts a new wave + * propagation. + * Sets: cell.dist = inf, cell.attrib.obs_pos = (-1,-1). + * + * @param x + * @param y + * @return Cell + */ + Cell makeFree(int x, int y) const; + /** + * @brief Updates distance map with `open` queue and brushfire algorithm. + * + * Reference: + * https://cs.gmu.edu/~kosecka/cs685/cs685-motion-planning.pdf + * + */ + void updateDistanceMap(); + +private: + int map_width_; + int map_height_; + + // distance map + std::vector dist_; + // attributes for each cell in distance map + std::vector attrib_; + // `open` priority queue + std::priority_queue, std::greater> open_; + + /** + * @brief Boundary check for map element/attribute access. + * + * @param x + * @param y + */ + bool isOutOfBound(int x, int y) const; + bool isOutOfBound(Eigen::Vector2i xy) const; + bool isOutOfBound(int x, int y, std::string& err_msg) const; + /** + * @brief Resize dist_ and attrib_ to default empty values of size + * (map_height, map_width). + * + * @param map_width + * @param map_height + */ + void allocateEmptyDistMap(int map_width, int map_height); +}; + +} // namespace skeletonizer +} // namespace cad2cav + +#endif /* __MAP_SKELETONIZER_DISTANCE_MAP_HPP__ */ diff --git a/map_skeletonizer/package.xml b/map_skeletonizer/package.xml new file mode 100644 index 0000000..f67bdd4 --- /dev/null +++ b/map_skeletonizer/package.xml @@ -0,0 +1,65 @@ + + + map_skeletonizer + 0.0.0 + The map_skeletonizer package + + + + + ryan + + + + + + TODO + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + catkin + cad2cav_types + roscpp + cad2cav_types + roscpp + cad2cav_types + roscpp + + + + + + + + diff --git a/map_skeletonizer/src/distance_map.cpp b/map_skeletonizer/src/distance_map.cpp new file mode 100644 index 0000000..512703f --- /dev/null +++ b/map_skeletonizer/src/distance_map.cpp @@ -0,0 +1,171 @@ +#include "map_skeletonizer/distance_map.hpp" + +#include + +#include + +namespace cad2cav { +namespace skeletonizer { + +DistanceMapBuilder::DistanceMapBuilder(const nav_msgs::OccupancyGrid& occ_grid, + int8_t cell_occupied_threshold) + : map_width_(occ_grid.info.width), map_height_(occ_grid.info.height) { + ROS_INFO("DistanceMap initialized with occupancy map: (%d, %d)", map_height_, + map_width_); + + allocateEmptyDistMap(map_width_, map_height_); + + for (int y = 0; y < map_height_; ++y) { + for (int x = 0; x < map_width_; ++x) { + // if the cell is occupied in occupancy map, push it into `open` queue + if (occ_grid.data[y * map_width_ + x] > cell_occupied_threshold && + !isOccupied(x, y)) { + open_.push(makeObstacle(x, y)); + } + } + } +} + +void DistanceMapBuilder::allocateEmptyDistMap(int map_width, int map_height) { + dist_.resize(map_height * map_width, std::numeric_limits::infinity()); + attrib_.resize(map_height * map_width, CellAttribute()); +} + +bool DistanceMapBuilder::isOutOfBound(int x, int y) const { + return (x >= map_width_ || x < 0 || y >= map_height_ || y < 0); +} + +bool DistanceMapBuilder::isOutOfBound(Eigen::Vector2i xy) const { + return isOutOfBound(xy.x(), xy.y()); +} + +bool DistanceMapBuilder::isOutOfBound(int x, int y, + std::string& err_msg) const { + err_msg = (boost::format( + "DistanceMapBuilder: %1% (%2%, %3%) out of bound (%4%, %5%)") % + err_msg % x % y % map_width_ % map_height_) + .str(); + return (x >= map_width_ || x < 0 || y >= map_height_ || y < 0); +} + +double& DistanceMapBuilder::distAt(int x, int y) { + std::string err_msg = "distance map access"; + if (isOutOfBound(x, y, err_msg)) { + throw ros::Exception(err_msg); + } + return dist_[y * map_width_ + x]; +} + +const double& DistanceMapBuilder::distAt(int x, int y) const { + std::string err_msg = "distance map access"; + if (isOutOfBound(x, y, err_msg)) { + throw ros::Exception(err_msg); + } + return dist_[y * map_width_ + x]; +} + +double& DistanceMapBuilder::distAt(Eigen::Vector2i xy) { + return distAt(xy.x(), xy.y()); +} + +const double& DistanceMapBuilder::distAt(Eigen::Vector2i xy) const { + return distAt(xy.x(), xy.y()); +} + +CellAttribute& DistanceMapBuilder::attributeAt(int x, int y) { + std::string err_msg = "cell attribute access"; + if (isOutOfBound(x, y, err_msg)) { + throw ros::Exception(err_msg); + } + return attrib_[y * map_width_ + x]; +} + +const CellAttribute& DistanceMapBuilder::attributeAt(int x, int y) const { + std::string err_msg = "cell attribute access"; + if (isOutOfBound(x, y, err_msg)) { + throw ros::Exception(err_msg); + } + return attrib_[y * map_width_ + x]; +} + +CellAttribute& DistanceMapBuilder::attributeAt(Eigen::Vector2i xy) { + return attributeAt(xy.x(), xy.y()); +} + +const CellAttribute& DistanceMapBuilder::attributeAt(Eigen::Vector2i xy) const { + return attributeAt(xy.x(), xy.y()); +} + +bool DistanceMapBuilder::isOccupied(int x, int y) const { + std::string err_msg = "isOccupied"; + if (isOutOfBound(x, y, err_msg)) { + throw ros::Exception(err_msg); + } + auto obs_pos = attributeAt(x, y).obs_pos; + return (obs_pos.x() == x && obs_pos.y() == y); +} + +bool DistanceMapBuilder::isOccupied(Eigen::Vector2i xy) const { + return isOccupied(xy.x(), xy.y()); +} + +Cell DistanceMapBuilder::makeObstacle(int x, int y) const { + std::string err_msg = "makeObstacle"; + if (isOutOfBound(x, y, err_msg)) { + throw ros::Exception(err_msg); + } + + Cell cell{Eigen::Vector2i(x, y), 0.0}; + cell.attrib.obs_pos = cell.pos; + return cell; +} + +Cell DistanceMapBuilder::makeFree(int x, int y) const { + std::string err_msg = "makeFree"; + if (isOutOfBound(x, y, err_msg)) { + throw ros::Exception(err_msg); + } + + Cell cell{Eigen::Vector2i(x, y), std::numeric_limits::infinity()}; + cell.attrib.obs_pos = Eigen::Vector2i(-1, -1); + cell.attrib.to_raise = true; + return cell; +} + +void DistanceMapBuilder::updateDistanceMap() { + static const std::vector neighbor_cells{ + {-1, -1}, {-1, 0}, {-1, 1}, {0, -1}, {0, 1}, {1, -1}, {1, 0}, {1, 1}}; + + while (!open_.empty()) { + Cell cell = open_.top(); + open_.pop(); + + if (cell.attrib.to_raise) { + // Raise + } else if (isOccupied(cell.attrib.obs_pos)) { + // Lower + cell.attrib.on_voronoi = false; + for (const auto& dxy : neighbor_cells) { + Eigen::Vector2i neighbor_pos = cell.pos + dxy; + if (isOutOfBound(neighbor_pos)) continue; + if (!attributeAt(neighbor_pos).to_raise) { + double new_distance = + (cell.attrib.obs_pos - neighbor_pos).squaredNorm(); + if (new_distance < distAt(neighbor_pos)) { + Cell neighbor_cell{neighbor_pos, new_distance}; + neighbor_cell.attrib.obs_pos = cell.attrib.obs_pos; + open_.push(neighbor_cell); + } else { + // chkVoro(s, n); + } + } + } + } + + distAt(cell.pos) = cell.dist; + attributeAt(cell.pos) = cell.attrib; + } +} + +} // namespace skeletonizer +} // namespace cad2cav