Skip to content

Commit

Permalink
Additional code facelift
Browse files Browse the repository at this point in the history
* Correct licensing years
* Fix Vector Object server dependencies
* Funcion rename for better readability
* Improve/fix comments

Signed-off-by: Alexey Merzlyakov <[email protected]>
  • Loading branch information
AlexeyMerzlyakov committed Feb 22, 2024
1 parent e2883b6 commit 67a16b0
Show file tree
Hide file tree
Showing 8 changed files with 28 additions and 19 deletions.
4 changes: 4 additions & 0 deletions nav2_map_server/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,8 @@ find_package(nav2_common REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(tf2_ros REQUIRED)
find_package(nav_msgs REQUIRED)
find_package(nav2_msgs REQUIRED)
find_package(yaml_cpp_vendor REQUIRED)
Expand Down Expand Up @@ -93,6 +95,8 @@ set(vo_server_dependencies
rclcpp
rclcpp_lifecycle
rclcpp_components
geometry_msgs
tf2_ros
nav_msgs
nav2_msgs
nav2_util)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -170,7 +170,7 @@ class VectorObjectServer : public nav2_util::LifecycleNode

/**
* @brief Callback for RemoveShapes service call.
* Try to remove all requested objects and switches map processing/publishing routine
* Try to remove requested vector objects and switches map processing/publishing routine
* @param request_header Service request header
* @param request Service request
* @param response Service response
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -128,7 +128,7 @@ class Shape
const double transform_tolerance) = 0;

/**
* @brief Gets shape boundaries.
* @brief Gets shape box-boundaries.
* Empty virtual method intended to be used in child implementations
* @param min_x output min X-boundary of shape
* @param min_y output min Y-boundary of shape
Expand Down Expand Up @@ -237,7 +237,7 @@ class Polygon : public Shape
const double transform_tolerance);

/**
* @brief Gets shape boundaries
* @brief Gets shape box-boundaries
* @param min_x output min X-boundary of shape
* @param min_y output min Y-boundary of shape
* @param max_x output max X-boundary of shape
Expand Down Expand Up @@ -347,7 +347,7 @@ class Circle : public Shape
const double transform_tolerance);

/**
* @brief Gets shape boundaries
* @brief Gets shape box-boundaries
* @param min_x output min X-boundary of shape
* @param min_y output min Y-boundary of shape
* @param max_x output max X-boundary of shape
Expand Down
24 changes: 12 additions & 12 deletions nav2_map_server/include/nav2_map_server/vector_object_utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,8 @@
#define NAV2_MAP_SERVER__VECTOR_OBJECT_UTILS_HPP_

#include <uuid/uuid.h>
#include <string>
#include <stdexcept>
#include <string>

#include "rclcpp/rclcpp.hpp"
#include "nav_msgs/msg/occupancy_grid.hpp"
Expand All @@ -32,7 +32,7 @@ namespace nav2_map_server
// ---------- Working with UUID-s ----------

/**
* @beirf Converts input UUID from input array to unparsed string
* @beirf Converts UUID from input array to unparsed string
* @param uuid Input UUID in array format
* @return Unparsed UUID string
*/
Expand All @@ -49,7 +49,7 @@ inline std::string unparseUUID(const unsigned char * uuid)
* @brief Declares and obtains ROS-parameter from given node
* @param node LifecycleNode pointer where the parameter belongs to
* @param param_name Parameter name string
* @param default_val Default value of the parameter (in case if parameter is not set)
* @param default_val Default value of the parameter (for the case if parameter is not set)
* @return Obtained parameter value
*/
template<typename ValT>
Expand Down Expand Up @@ -94,7 +94,7 @@ enum class OverlayType : uint8_t

/**
* @brief Updates map value with shape's one according to the given overlay type
* @param map_val Map value. To be updated with new value if overlay is required
* @param map_val Map value. To be updated with new value if overlay is involved
* @param shape_val Vector object value to be overlayed on map
* @param overlay_type Type of overlay
* @throw std::exception in case of unknown overlay type
Expand Down Expand Up @@ -125,13 +125,13 @@ inline void processVal(
}

/**
* @brief Fill the cell on the map with given shape value according to the given overlay type
* @param map Output map to be filled with
* @param offset Offset to the cell to be filled
* @param shape_val Vector object value to be overlayed on map
* @brief Updates the cell on the map with given shape value according to the given overlay type
* @param map Output map to be updated with
* @param offset Offset to the cell to be updated
* @param shape_val Vector object value to be updated map with
* @param overlay_type Type of overlay
*/
inline void fillMap(
inline void processCell(
nav_msgs::msg::OccupancyGrid::SharedPtr map,
const unsigned int offset,
const int8_t shape_val,
Expand All @@ -148,7 +148,7 @@ class MapAction
public:
/**
* @brief MapAction constructor
* @param map Output map pointer
* @param map Pointer to output map
* @param value Value to put on map
* @param overlay_type Overlay type
*/
Expand All @@ -159,12 +159,12 @@ class MapAction
{}

/**
* @brief Map filling operator
* @brief Map' cell updating operator
* @param offset Offset on the map where the cell to be changed
*/
inline void operator()(unsigned int offset)
{
fillMap(map_, offset, value_, overlay_type_);
processCell(map_, offset, value_, overlay_type_);
}

protected:
Expand Down
2 changes: 2 additions & 0 deletions nav2_map_server/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,9 @@
<depend>yaml_cpp_vendor</depend>
<depend>launch_ros</depend>
<depend>launch_testing</depend>
<depend>geometry_msgs</depend>
<depend>tf2</depend>
<depend>tf2_ros</depend>
<depend>nav2_msgs</depend>
<depend>nav2_util</depend>
<depend>graphicsmagick</depend>
Expand Down
2 changes: 1 addition & 1 deletion nav2_map_server/src/vo_server/vector_object_shapes.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -563,7 +563,7 @@ inline void Circle::putPoint(
nav_msgs::msg::OccupancyGrid::SharedPtr map,
const OverlayType overlay_type)
{
fillMap(map, my * map->info.width + mx, params_->value, overlay_type);
processCell(map, my * map->info.width + mx, params_->value, overlay_type);
}

} // namespace nav2_map_server
2 changes: 1 addition & 1 deletion nav2_util/include/nav2_util/polygon_utils.hpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright (c) 2023 Samsung R&D Institute Russia
// Copyright (c) 2022 Samsung R&D Institute Russia
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down
5 changes: 4 additions & 1 deletion nav2_util/test/regression/map_bresenham_2d.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright (c) 2023 Samsung R&D Institute Russia
// Copyright (c) 2022 Samsung R&D Institute Russia
// All rights reserved.
//
// Software License Agreement (BSD License 2.0)
Expand Down Expand Up @@ -38,6 +38,9 @@

#include "nav2_util/raytrace_line_2d.hpp"

// MapAction - is a functor class used to cover raytraceLine algorithm.
// It contains char map inside, which is an abstract one and not related
// to any concrete representation (like Costmap2D or OccupancyGrid).
class MapAction
{
public:
Expand Down

0 comments on commit 67a16b0

Please sign in to comment.