Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
costmap.cpp
1 // Copyright (c) 2018 Intel Corporation
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include <vector>
16 #include <algorithm>
17 #include "nav2_util/costmap.hpp"
18 #include "tf2/LinearMath/Quaternion.h"
19 #include "nav2_util/geometry_utils.hpp"
20 
21 using std::vector;
22 
23 namespace nav2_util
24 {
25 using nav2_util::geometry_utils::orientationAroundZAxis;
26 
27 const Costmap::CostValue Costmap::no_information = 255;
28 const Costmap::CostValue Costmap::lethal_obstacle = 254;
29 const Costmap::CostValue Costmap::inscribed_inflated_obstacle = 253;
30 const Costmap::CostValue Costmap::medium_cost = 128;
31 const Costmap::CostValue Costmap::free_space = 0;
32 
33 // TODO(orduno): Port ROS1 Costmap package
34 Costmap::Costmap(
35  rclcpp::Node * node, bool trinary_costmap, bool track_unknown_space,
36  int lethal_threshold, int unknown_cost_value)
37 : node_(node), trinary_costmap_(trinary_costmap), track_unknown_space_(track_unknown_space),
38  lethal_threshold_(lethal_threshold), unknown_cost_value_(unknown_cost_value)
39 {
40  if (lethal_threshold_ < 0. || lethal_threshold_ > 100.) {
41  RCLCPP_WARN(
42  node_->get_logger(), "Costmap: Lethal threshold set to %d, it should be within"
43  " bounds 0-100. This could result in potential collisions!", lethal_threshold_);
44  // lethal_threshold_ = std::max(std::min(lethal_threshold_, 100), 0);
45  }
46 }
47 
48 Costmap::~Costmap()
49 {
50 }
51 
52 void Costmap::set_static_map(const nav_msgs::msg::OccupancyGrid & occupancy_grid)
53 {
54  RCLCPP_INFO(node_->get_logger(), "Costmap: Setting static costmap");
55 
56  costmap_properties_.map_load_time = node_->now();
57  costmap_properties_.update_time = node_->now();
58  costmap_properties_.layer = "Master";
59 
60  // Store the properties of the occupancy grid
61  costmap_properties_.resolution = occupancy_grid.info.resolution;
62  costmap_properties_.size_x = occupancy_grid.info.width;
63  costmap_properties_.size_y = occupancy_grid.info.height;
64  costmap_properties_.origin = occupancy_grid.info.origin;
65 
66  uint32_t size_x = costmap_properties_.size_x;
67  uint32_t size_y = costmap_properties_.size_y;
68 
69  costs_.resize(size_x * size_y);
70 
71  // TODO(orduno): for now just doing a direct mapping of values from the original static map
72  // i.e. no cell inflation, etc.
73  std::vector<int8_t> static_map_cell_values = occupancy_grid.data;
74 
75  unsigned int index = 0;
76  for (unsigned int i = 0; i < size_y; ++i) {
77  for (unsigned int j = 0; j < size_x; ++j) {
78  unsigned char value = static_map_cell_values[index];
79  costs_[index] = interpret_value(value);
80  ++index;
81  }
82  }
83 
84  map_provided_ = true;
85 }
86 
87 void Costmap::set_test_costmap(const TestCostmap & testCostmapType)
88 {
89  costmap_properties_.map_load_time = node_->now();
90  costmap_properties_.update_time = node_->now();
91  costmap_properties_.layer = "master";
92  costmap_properties_.resolution = 1;
93  costmap_properties_.size_x = 10;
94  costmap_properties_.size_y = 10;
95  costmap_properties_.origin.position.x = 0.0;
96  costmap_properties_.origin.position.y = 0.0;
97  costmap_properties_.origin.position.z = 0.0;
98 
99  // Define map rotation
100  // Provided as yaw with counterclockwise rotation, with yaw = 0 meaning no rotation
101  costmap_properties_.origin.orientation = orientationAroundZAxis(0.0);
102 
103  costs_ = get_test_data(testCostmapType);
104 
105  using_test_map_ = true;
106 }
107 
108 nav2_msgs::msg::Costmap Costmap::get_costmap(
109  const nav2_msgs::msg::CostmapMetaData & /*specifications*/)
110 {
111  if (!map_provided_ && !using_test_map_) {
112  throw std::runtime_error("Costmap has not been set.");
113  }
114 
115  // TODO(orduno): build a costmap given the specifications
116  // for now using the specs of the static map
117 
118  nav2_msgs::msg::Costmap costmap;
119 
120  costmap.header.stamp = node_->now();
121  costmap.header.frame_id = "map";
122  costmap.metadata = costmap_properties_;
123  costmap.data = costs_;
124 
125  return costmap;
126 }
127 
128 vector<uint8_t> Costmap::get_test_data(const TestCostmap testCostmapType)
129 {
130  // TODO(orduno): alternatively use a mathematical function
131 
132  const uint8_t n = no_information;
133  const uint8_t x = lethal_obstacle;
134  const uint8_t i = inscribed_inflated_obstacle;
135  const uint8_t u = medium_cost;
136  const uint8_t o = free_space;
137 
138  vector<uint8_t> costmapFree =
139  // 0 1 2 3 4 5 6 7 8 9
140  {o, o, o, o, o, o, o, o, o, o, // 0
141  o, o, o, o, o, o, o, o, o, o, // 1
142  o, o, o, o, o, o, o, o, o, o, // 2
143  o, o, o, o, o, o, o, o, o, o, // 3
144  o, o, o, o, o, o, o, o, o, o, // 4
145  o, o, o, o, o, o, o, o, o, o, // 5
146  o, o, o, o, o, o, o, o, o, o, // 6
147  o, o, o, o, o, o, o, o, o, o, // 7
148  o, o, o, o, o, o, o, o, o, o, // 8
149  o, o, o, o, o, o, o, o, o, o}; // 9
150 
151  vector<uint8_t> costmapBounded =
152  // 0 1 2 3 4 5 6 7 8 9
153  {n, n, n, n, n, n, n, n, n, n, // 0
154  n, o, o, o, o, o, o, o, o, n, // 1
155  n, o, o, o, o, o, o, o, o, n, // 2
156  n, o, o, o, o, o, o, o, o, n, // 3
157  n, o, o, o, o, o, o, o, o, n, // 4
158  n, o, o, o, o, o, o, o, o, n, // 5
159  n, o, o, o, o, o, o, o, o, n, // 6
160  n, o, o, o, o, o, o, o, o, n, // 7
161  n, o, o, o, o, o, o, o, o, n, // 8
162  n, n, n, n, n, n, n, n, n, n}; // 9
163 
164  vector<uint8_t> costmapObstacleBL =
165  // 0 1 2 3 4 5 6 7 8 9
166  {n, n, n, n, n, n, n, n, n, n, // 0
167  n, o, o, o, o, o, o, o, o, n, // 1
168  n, o, o, o, o, o, o, o, o, n, // 2
169  n, o, o, o, o, o, o, o, o, n, // 3
170  n, o, o, o, o, o, o, o, o, n, // 4
171  n, o, x, x, x, o, o, o, o, n, // 5
172  n, o, x, x, x, o, o, o, o, n, // 6
173  n, o, x, x, x, o, o, o, o, n, // 7
174  n, o, o, o, o, o, o, o, o, n, // 8
175  n, n, n, n, n, n, n, n, n, n}; // 9
176 
177  vector<uint8_t> costmapObstacleTL =
178  // 0 1 2 3 4 5 6 7 8 9
179  {n, n, n, n, n, n, n, n, n, n, // 0
180  n, o, o, o, o, o, o, o, o, n, // 1
181  n, o, x, x, x, o, o, o, o, n, // 2
182  n, o, x, x, x, o, o, o, o, n, // 3
183  n, o, x, x, x, o, o, o, o, n, // 4
184  n, o, o, o, o, o, o, o, o, n, // 5
185  n, o, o, o, o, o, o, o, o, n, // 6
186  n, o, o, o, o, o, o, o, o, n, // 7
187  n, o, o, o, o, o, o, o, o, n, // 8
188  n, n, n, n, n, n, n, n, n, n}; // 9
189 
190  vector<uint8_t> costmapMaze =
191  // 0 1 2 3 4 5 6 7 8 9
192  {n, n, n, n, n, n, n, n, n, n, // 0
193  n, o, o, o, o, o, o, o, o, n, // 1
194  n, x, x, o, x, x, x, o, x, n, // 2
195  n, o, o, o, o, x, o, o, o, n, // 3
196  n, o, x, x, o, x, o, x, o, n, // 4
197  n, o, x, x, o, x, o, x, o, n, // 5
198  n, o, o, x, o, x, o, x, o, n, // 6
199  n, x, o, x, o, x, o, x, o, n, // 7
200  n, o, o, o, o, o, o, x, o, n, // 8
201  n, n, n, n, n, n, n, n, n, n}; // 9
202 
203  vector<uint8_t> costmapMaze2 =
204  // 0 1 2 3 4 5 6 7 8 9
205  {n, n, n, n, n, n, n, n, n, n, // 0
206  n, o, o, o, o, o, o, o, o, n, // 1
207  n, x, x, u, x, x, x, o, x, n, // 2
208  n, o, o, o, o, o, o, o, u, n, // 3
209  n, o, x, x, o, x, x, x, u, n, // 4
210  n, o, x, x, o, o, o, x, u, n, // 5
211  n, o, o, x, u, x, o, x, u, n, // 6
212  n, x, o, x, u, x, i, x, u, n, // 7
213  n, o, o, o, o, o, o, o, o, n, // 8
214  n, n, n, n, n, n, n, n, n, n}; // 9
215 
216  switch (testCostmapType) {
217  case TestCostmap::open_space:
218  return costmapFree;
219  case TestCostmap::bounded:
220  return costmapBounded;
221  case TestCostmap::bottom_left_obstacle:
222  return costmapObstacleBL;
223  case TestCostmap::top_left_obstacle:
224  return costmapObstacleTL;
225  case TestCostmap::maze1:
226  return costmapMaze;
227  case TestCostmap::maze2:
228  return costmapMaze2;
229  default:
230  return costmapFree;
231  }
232 }
233 
234 uint8_t Costmap::interpret_value(const int8_t value) const
235 {
236  if (track_unknown_space_ && value == unknown_cost_value_) {
237  return no_information;
238  } else if (!track_unknown_space_ && value == unknown_cost_value_) {
239  return free_space;
240  } else if (value >= lethal_threshold_) {
241  return lethal_obstacle;
242  } else if (trinary_costmap_) {
243  return free_space;
244  }
245 
246  double scale = static_cast<double>(value / lethal_threshold_);
247  return static_cast<uint8_t>(scale * lethal_obstacle);
248 }
249 
250 bool Costmap::is_free(const unsigned int x_coordinate, const unsigned int y_coordinate) const
251 {
252  unsigned int index = y_coordinate * costmap_properties_.size_x + x_coordinate;
253 
254  return is_free(index);
255 }
256 
257 bool Costmap::is_free(const unsigned int index) const
258 {
259  if (costs_[index] < Costmap::inscribed_inflated_obstacle) {
260  return true;
261  }
262 
263  return false;
264 }
265 
266 } // namespace nav2_util
bool is_free(const unsigned int x_coordinate, const unsigned int y_coordinate) const
Get whether some coordinates are free.
Definition: costmap.cpp:250
void set_static_map(const nav_msgs::msg::OccupancyGrid &occupancy_grid)
Set the static map of this costmap.
Definition: costmap.cpp:52
void set_test_costmap(const TestCostmap &testCostmapType)
Set the test costmap type of this costmap.
Definition: costmap.cpp:87
nav2_msgs::msg::Costmap get_costmap(const nav2_msgs::msg::CostmapMetaData &specifications)
Get a costmap message from this object.
Definition: costmap.cpp:108