17 #include "nav2_util/costmap.hpp"
18 #include "tf2/LinearMath/Quaternion.hpp"
19 #include "nav2_util/geometry_utils.hpp"
25 using nav2_util::geometry_utils::orientationAroundZAxis;
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;
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)
40 if (lethal_threshold_ < 0. || lethal_threshold_ > 100.) {
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_);
54 RCLCPP_INFO(node_->get_logger(),
"Costmap: Setting static costmap");
56 costmap_properties_.map_load_time = node_->now();
57 costmap_properties_.update_time = node_->now();
58 costmap_properties_.layer =
"Master";
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;
66 uint32_t size_x = costmap_properties_.size_x;
67 uint32_t size_y = costmap_properties_.size_y;
69 costs_.resize(size_x * size_y);
73 std::vector<int8_t> static_map_cell_values = occupancy_grid.data;
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);
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;
101 costmap_properties_.origin.orientation = orientationAroundZAxis(0.0);
103 costs_ = get_test_data(testCostmapType);
105 using_test_map_ =
true;
109 const nav2_msgs::msg::CostmapMetaData & )
111 if (!map_provided_ && !using_test_map_) {
112 throw std::runtime_error(
"Costmap has not been set.");
118 nav2_msgs::msg::Costmap costmap;
120 costmap.header.stamp = node_->now();
121 costmap.header.frame_id =
"map";
122 costmap.metadata = costmap_properties_;
123 costmap.data = costs_;
128 vector<uint8_t> Costmap::get_test_data(
const TestCostmap testCostmapType)
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;
138 vector<uint8_t> costmapFree =
140 {o, o, o, o, o, o, o, o, o, o,
141 o, o, o, o, o, o, o, o, o, o,
142 o, o, o, o, o, o, o, o, o, o,
143 o, o, o, o, o, o, o, o, o, o,
144 o, o, o, o, o, o, o, o, o, o,
145 o, o, o, o, o, o, o, o, o, o,
146 o, o, o, o, o, o, o, o, o, o,
147 o, o, o, o, o, o, o, o, o, o,
148 o, o, o, o, o, o, o, o, o, o,
149 o, o, o, o, o, o, o, o, o, o};
151 vector<uint8_t> costmapBounded =
153 {n, n, n, n, n, n, n, n, n, n,
154 n, o, o, o, o, o, o, o, o, n,
155 n, o, o, o, o, o, o, o, o, n,
156 n, o, o, o, o, o, o, o, o, n,
157 n, o, o, o, o, o, o, o, o, n,
158 n, o, o, o, o, o, o, o, o, n,
159 n, o, o, o, o, o, o, o, o, n,
160 n, o, o, o, o, o, o, o, o, n,
161 n, o, o, o, o, o, o, o, o, n,
162 n, n, n, n, n, n, n, n, n, n};
164 vector<uint8_t> costmapObstacleBL =
166 {n, n, n, n, n, n, n, n, n, n,
167 n, o, o, o, o, o, o, o, o, n,
168 n, o, o, o, o, o, o, o, o, n,
169 n, o, o, o, o, o, o, o, o, n,
170 n, o, o, o, o, o, o, o, o, n,
171 n, o, x, x, x, o, o, o, o, n,
172 n, o, x, x, x, o, o, o, o, n,
173 n, o, x, x, x, o, o, o, o, n,
174 n, o, o, o, o, o, o, o, o, n,
175 n, n, n, n, n, n, n, n, n, n};
177 vector<uint8_t> costmapObstacleTL =
179 {n, n, n, n, n, n, n, n, n, n,
180 n, o, o, o, o, o, o, o, o, n,
181 n, o, x, x, x, o, o, o, o, n,
182 n, o, x, x, x, o, o, o, o, n,
183 n, o, x, x, x, o, o, o, o, n,
184 n, o, o, o, o, o, o, o, o, n,
185 n, o, o, o, o, o, o, o, o, n,
186 n, o, o, o, o, o, o, o, o, n,
187 n, o, o, o, o, o, o, o, o, n,
188 n, n, n, n, n, n, n, n, n, n};
190 vector<uint8_t> costmapMaze =
192 {n, n, n, n, n, n, n, n, n, n,
193 n, o, o, o, o, o, o, o, o, n,
194 n, x, x, o, x, x, x, o, x, n,
195 n, o, o, o, o, x, o, o, o, n,
196 n, o, x, x, o, x, o, x, o, n,
197 n, o, x, x, o, x, o, x, o, n,
198 n, o, o, x, o, x, o, x, o, n,
199 n, x, o, x, o, x, o, x, o, n,
200 n, o, o, o, o, o, o, x, o, n,
201 n, n, n, n, n, n, n, n, n, n};
203 vector<uint8_t> costmapMaze2 =
205 {n, n, n, n, n, n, n, n, n, n,
206 n, o, o, o, o, o, o, o, o, n,
207 n, x, x, u, x, x, x, o, x, n,
208 n, o, o, o, o, o, o, o, u, n,
209 n, o, x, x, o, x, x, x, u, n,
210 n, o, x, x, o, o, o, x, u, n,
211 n, o, o, x, u, x, o, x, u, n,
212 n, x, o, x, u, x, i, x, u, n,
213 n, o, o, o, o, o, o, o, o, n,
214 n, n, n, n, n, n, n, n, n, n};
216 switch (testCostmapType) {
217 case TestCostmap::open_space:
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:
227 case TestCostmap::maze2:
234 uint8_t Costmap::interpret_value(
const int8_t value)
const
236 if (track_unknown_space_ && value == unknown_cost_value_) {
237 return no_information;
238 }
else if (!track_unknown_space_ && value == unknown_cost_value_) {
240 }
else if (value >= lethal_threshold_) {
241 return lethal_obstacle;
242 }
else if (trinary_costmap_) {
246 double scale =
static_cast<double>(value / lethal_threshold_);
247 return static_cast<uint8_t
>(scale * lethal_obstacle);
250 bool Costmap::is_free(
const unsigned int x_coordinate,
const unsigned int y_coordinate)
const
252 unsigned int index = y_coordinate * costmap_properties_.size_x + x_coordinate;
259 if (costs_[index] < Costmap::inscribed_inflated_obstacle) {
bool is_free(const unsigned int x_coordinate, const unsigned int y_coordinate) const
Get whether some coordinates are free.
void set_static_map(const nav_msgs::msg::OccupancyGrid &occupancy_grid)
Set the static map of this costmap.
void set_test_costmap(const TestCostmap &testCostmapType)
Set the test costmap type of this costmap.
nav2_msgs::msg::Costmap get_costmap(const nav2_msgs::msg::CostmapMetaData &specifications)
Get a costmap message from this object.