Skip to content

Commit 2a46ab5

Browse files
Additional code facelift
* Correct licensing years * Fix Vector Object server dependencies * Funcion rename for better readability * Improve/fix comments
1 parent fe1c0dd commit 2a46ab5

File tree

8 files changed

+28
-19
lines changed

8 files changed

+28
-19
lines changed

nav2_map_server/CMakeLists.txt

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,8 @@ find_package(nav2_common REQUIRED)
88
find_package(rclcpp REQUIRED)
99
find_package(rclcpp_lifecycle REQUIRED)
1010
find_package(rclcpp_components REQUIRED)
11+
find_package(geometry_msgs REQUIRED)
12+
find_package(tf2_ros REQUIRED)
1113
find_package(nav_msgs REQUIRED)
1214
find_package(nav2_msgs REQUIRED)
1315
find_package(yaml_cpp_vendor REQUIRED)
@@ -93,6 +95,8 @@ set(vo_server_dependencies
9395
rclcpp
9496
rclcpp_lifecycle
9597
rclcpp_components
98+
geometry_msgs
99+
tf2_ros
96100
nav_msgs
97101
nav2_msgs
98102
nav2_util)

nav2_map_server/include/nav2_map_server/vector_object_server.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -170,7 +170,7 @@ class VectorObjectServer : public nav2_util::LifecycleNode
170170

171171
/**
172172
* @brief Callback for RemoveShapes service call.
173-
* Try to remove all requested objects and switches map processing/publishing routine
173+
* Try to remove requested vector objects and switches map processing/publishing routine
174174
* @param request_header Service request header
175175
* @param request Service request
176176
* @param response Service response

nav2_map_server/include/nav2_map_server/vector_object_shapes.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -128,7 +128,7 @@ class Shape
128128
const double transform_tolerance) = 0;
129129

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

239239
/**
240-
* @brief Gets shape boundaries
240+
* @brief Gets shape box-boundaries
241241
* @param min_x output min X-boundary of shape
242242
* @param min_y output min Y-boundary of shape
243243
* @param max_x output max X-boundary of shape
@@ -347,7 +347,7 @@ class Circle : public Shape
347347
const double transform_tolerance);
348348

349349
/**
350-
* @brief Gets shape boundaries
350+
* @brief Gets shape box-boundaries
351351
* @param min_x output min X-boundary of shape
352352
* @param min_y output min Y-boundary of shape
353353
* @param max_x output max X-boundary of shape

nav2_map_server/include/nav2_map_server/vector_object_utils.hpp

Lines changed: 12 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -16,8 +16,8 @@
1616
#define NAV2_MAP_SERVER__VECTOR_OBJECT_UTILS_HPP_
1717

1818
#include <uuid/uuid.h>
19-
#include <string>
2019
#include <stdexcept>
20+
#include <string>
2121

2222
#include "rclcpp/rclcpp.hpp"
2323
#include "nav_msgs/msg/occupancy_grid.hpp"
@@ -32,7 +32,7 @@ namespace nav2_map_server
3232
// ---------- Working with UUID-s ----------
3333

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

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

127127
/**
128-
* @brief Fill the cell on the map with given shape value according to the given overlay type
129-
* @param map Output map to be filled with
130-
* @param offset Offset to the cell to be filled
131-
* @param shape_val Vector object value to be overlayed on map
128+
* @brief Updates the cell on the map with given shape value according to the given overlay type
129+
* @param map Output map to be updated with
130+
* @param offset Offset to the cell to be updated
131+
* @param shape_val Vector object value to be updated map with
132132
* @param overlay_type Type of overlay
133133
*/
134-
inline void fillMap(
134+
inline void processCell(
135135
nav_msgs::msg::OccupancyGrid::SharedPtr map,
136136
const unsigned int offset,
137137
const int8_t shape_val,
@@ -148,7 +148,7 @@ class MapAction
148148
public:
149149
/**
150150
* @brief MapAction constructor
151-
* @param map Output map pointer
151+
* @param map Pointer to output map
152152
* @param value Value to put on map
153153
* @param overlay_type Overlay type
154154
*/
@@ -159,12 +159,12 @@ class MapAction
159159
{}
160160

161161
/**
162-
* @brief Map filling operator
162+
* @brief Map' cell updating operator
163163
* @param offset Offset on the map where the cell to be changed
164164
*/
165165
inline void operator()(unsigned int offset)
166166
{
167-
fillMap(map_, offset, value_, overlay_type_);
167+
processCell(map_, offset, value_, overlay_type_);
168168
}
169169

170170
protected:

nav2_map_server/package.xml

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,9 @@
2121
<depend>yaml_cpp_vendor</depend>
2222
<depend>launch_ros</depend>
2323
<depend>launch_testing</depend>
24+
<depend>geometry_msgs</depend>
2425
<depend>tf2</depend>
26+
<depend>tf2_ros</depend>
2527
<depend>nav2_msgs</depend>
2628
<depend>nav2_util</depend>
2729
<depend>graphicsmagick</depend>

nav2_map_server/src/vo_server/vector_object_shapes.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -563,7 +563,7 @@ inline void Circle::putPoint(
563563
nav_msgs::msg::OccupancyGrid::SharedPtr map,
564564
const OverlayType overlay_type)
565565
{
566-
fillMap(map, my * map->info.width + mx, params_->value, overlay_type);
566+
processCell(map, my * map->info.width + mx, params_->value, overlay_type);
567567
}
568568

569569
} // namespace nav2_map_server

nav2_util/include/nav2_util/polygon_utils.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright (c) 2023 Samsung R&D Institute Russia
1+
// Copyright (c) 2022 Samsung R&D Institute Russia
22
//
33
// Licensed under the Apache License, Version 2.0 (the "License");
44
// you may not use this file except in compliance with the License.

nav2_util/test/regression/map_bresenham_2d.cpp

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright (c) 2023 Samsung R&D Institute Russia
1+
// Copyright (c) 2022 Samsung R&D Institute Russia
22
// All rights reserved.
33
//
44
// Software License Agreement (BSD License 2.0)
@@ -38,6 +38,9 @@
3838

3939
#include "nav2_util/raytrace_line_2d.hpp"
4040

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

0 commit comments

Comments
 (0)