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 */
5555template <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
148148public:
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
170170protected:
0 commit comments