Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
voxel_grid.cpp
1 /*********************************************************************
2 *
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2008, Willow Garage, Inc.
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of the Willow Garage nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *
35 * Author: Eitan Marder-Eppstein
36 *********************************************************************/
37 #include <nav2_voxel_grid/voxel_grid.hpp>
38 
39 #include <rclcpp/logger.hpp>
40 #include <rclcpp/logging.hpp>
41 
42 namespace nav2_voxel_grid
43 {
44 VoxelGrid::VoxelGrid(unsigned int size_x, unsigned int size_y, unsigned int size_z)
45 : logger(rclcpp::get_logger("voxel_grid"))
46 {
47  size_x_ = size_x;
48  size_y_ = size_y;
49  size_z_ = size_z;
50 
51  if (size_z_ > 16) {
52  RCLCPP_INFO(
53  logger, "Error, this implementation can only support up to 16 z values (%d)",
54  size_z_);
55  size_z_ = 16;
56  }
57 
58  data_ = new uint32_t[size_x_ * size_y_];
59  uint32_t unknown_col = ~((uint32_t)0) >> 16;
60  uint32_t * col = data_;
61  for (unsigned int i = 0; i < size_x_ * size_y_; ++i) {
62  *col = unknown_col;
63  ++col;
64  }
65 }
66 
67 void VoxelGrid::resize(unsigned int size_x, unsigned int size_y, unsigned int size_z)
68 {
69  // if we're not actually changing the size, we can just reset things
70  if (size_x == size_x_ && size_y == size_y_ && size_z == size_z_) {
71  reset();
72  return;
73  }
74 
75  delete[] data_;
76  size_x_ = size_x;
77  size_y_ = size_y;
78  size_z_ = size_z;
79 
80  if (size_z_ > 16) {
81  RCLCPP_INFO(
82  logger, "Error, this implementation can only support up to 16 z values (%d)",
83  size_z);
84  size_z_ = 16;
85  }
86 
87  data_ = new uint32_t[size_x_ * size_y_];
88  uint32_t unknown_col = ~((uint32_t)0) >> 16;
89  uint32_t * col = data_;
90  for (unsigned int i = 0; i < size_x_ * size_y_; ++i) {
91  *col = unknown_col;
92  ++col;
93  }
94 }
95 
96 VoxelGrid::~VoxelGrid()
97 {
98  delete[] data_;
99 }
100 
101 void VoxelGrid::reset()
102 {
103  uint32_t unknown_col = ~((uint32_t)0) >> 16;
104  uint32_t * col = data_;
105  for (unsigned int i = 0; i < size_x_ * size_y_; ++i) {
106  *col = unknown_col;
107  ++col;
108  }
109 }
110 
111 void VoxelGrid::markVoxelLine(
112  double x0, double y0, double z0, double x1, double y1, double z1,
113  unsigned int max_length)
114 {
115  if (x0 >= size_x_ || y0 >= size_y_ || z0 >= size_z_ || x1 >= size_x_ || y1 >= size_y_ ||
116  z1 >= size_z_)
117  {
118  RCLCPP_DEBUG(
119  logger,
120  "Error, line endpoint out of bounds. "
121  "(%.2f, %.2f, %.2f) to (%.2f, %.2f, %.2f), size: (%d, %d, %d)",
122  x0, y0, z0, x1, y1, z1, size_x_, size_y_, size_z_);
123  return;
124  }
125 
126  MarkVoxel mv(data_);
127  raytraceLine(mv, x0, y0, z0, x1, y1, z1, max_length);
128 }
129 
130 void VoxelGrid::clearVoxelLine(
131  double x0, double y0, double z0, double x1, double y1, double z1,
132  unsigned int max_length, unsigned int min_length)
133 {
134  if (x0 >= size_x_ || y0 >= size_y_ || z0 >= size_z_ || x1 >= size_x_ || y1 >= size_y_ ||
135  z1 >= size_z_)
136  {
137  RCLCPP_DEBUG(
138  logger,
139  "Error, line endpoint out of bounds. "
140  "(%.2f, %.2f, %.2f) to (%.2f, %.2f, %.2f), size: (%d, %d, %d)",
141  x0, y0, z0, x1, y1, z1, size_x_, size_y_, size_z_);
142  return;
143  }
144 
145  ClearVoxel cv(data_);
146  raytraceLine(cv, x0, y0, z0, x1, y1, z1, max_length, min_length);
147 }
148 
149 void VoxelGrid::clearVoxelLineInMap(
150  double x0, double y0, double z0, double x1, double y1, double z1, unsigned char * map_2d,
151  unsigned int unknown_threshold, unsigned int mark_threshold, unsigned char free_cost,
152  unsigned char unknown_cost, unsigned int max_length, unsigned int min_length)
153 {
154  costmap = map_2d;
155  if (map_2d == NULL) {
156  clearVoxelLine(x0, y0, z0, x1, y1, z1, max_length, min_length);
157  return;
158  }
159 
160  if (x0 >= size_x_ || y0 >= size_y_ || z0 >= size_z_ || x1 >= size_x_ || y1 >= size_y_ ||
161  z1 >= size_z_)
162  {
163  RCLCPP_DEBUG(
164  logger,
165  "Error, line endpoint out of bounds. "
166  "(%.2f, %.2f, %.2f) to (%.2f, %.2f, %.2f), size: (%d, %d, %d)",
167  x0, y0, z0, x1, y1, z1, size_x_, size_y_, size_z_);
168  return;
169  }
170 
171  ClearVoxelInMap cvm(data_, costmap, unknown_threshold, mark_threshold, free_cost, unknown_cost);
172  raytraceLine(cvm, x0, y0, z0, x1, y1, z1, max_length, min_length);
173 }
174 
175 VoxelStatus VoxelGrid::getVoxel(unsigned int x, unsigned int y, unsigned int z)
176 {
177  if (x >= size_x_ || y >= size_y_ || z >= size_z_) {
178  RCLCPP_DEBUG(logger, "Error, voxel out of bounds. (%d, %d, %d)\n", x, y, z);
179  return UNKNOWN;
180  }
181  uint32_t full_mask = ((uint32_t)1 << z << 16) | (1 << z);
182  uint32_t result = data_[y * size_x_ + x] & full_mask;
183  unsigned int bits = numBits(result);
184 
185  // known marked: 11 = 2 bits, unknown: 01 = 1 bit, known free: 00 = 0 bits
186  if (bits < 2) {
187  if (bits < 1) {
188  return FREE;
189  }
190 
191  return UNKNOWN;
192  }
193 
194  return MARKED;
195 }
196 
197 VoxelStatus VoxelGrid::getVoxelColumn(
198  unsigned int x, unsigned int y,
199  unsigned int unknown_threshold, unsigned int marked_threshold)
200 {
201  if (x >= size_x_ || y >= size_y_) {
202  RCLCPP_DEBUG(logger, "Error, voxel out of bounds. (%d, %d)\n", x, y);
203  return UNKNOWN;
204  }
205 
206  uint32_t * col = &data_[y * size_x_ + x];
207 
208  unsigned int unknown_bits = uint16_t(*col >> 16) ^ uint16_t(*col);
209  unsigned int marked_bits = *col >> 16;
210 
211  // check if the number of marked bits qualifies the col as marked
212  if (!bitsBelowThreshold(marked_bits, marked_threshold)) {
213  return MARKED;
214  }
215 
216  // check if the number of unknown bits qualifies the col as unknown
217  if (!bitsBelowThreshold(unknown_bits, unknown_threshold)) {
218  return UNKNOWN;
219  }
220 
221  return FREE;
222 }
223 
224 unsigned int VoxelGrid::sizeX()
225 {
226  return size_x_;
227 }
228 
229 unsigned int VoxelGrid::sizeY()
230 {
231  return size_y_;
232 }
233 
234 unsigned int VoxelGrid::sizeZ()
235 {
236  return size_z_;
237 }
238 
239 void VoxelGrid::printVoxelGrid()
240 {
241  for (unsigned int z = 0; z < size_z_; z++) {
242  printf("Layer z = %u:\n", z);
243  for (unsigned int y = 0; y < size_y_; y++) {
244  for (unsigned int x = 0; x < size_x_; x++) {
245  printf((getVoxel(x, y, z)) == nav2_voxel_grid::MARKED ? "#" : " ");
246  }
247  printf("|\n");
248  }
249  }
250 }
251 
252 void VoxelGrid::printColumnGrid()
253 {
254  printf("Column view:\n");
255  for (unsigned int y = 0; y < size_y_; y++) {
256  for (unsigned int x = 0; x < size_x_; x++) {
257  printf((getVoxelColumn(x, y, 16, 0) == nav2_voxel_grid::MARKED) ? "#" : " ");
258  }
259  printf("|\n");
260  }
261 }
262 } // namespace nav2_voxel_grid
void resize(unsigned int size_x, unsigned int size_y, unsigned int size_z)
Resizes a voxel grid to the desired size.
Definition: voxel_grid.cpp:67
VoxelGrid(unsigned int size_x, unsigned int size_y, unsigned int size_z)
Constructor for a voxel grid.
Definition: voxel_grid.cpp:44