31 #include <geometry_msgs/PolygonStamped.h>
32 #include <nav_msgs/OccupancyGrid.h>
33 #include <sensor_msgs/PointCloud.h>
39 #include <costmap_cspace_msgs/CSpace3D.h>
40 #include <costmap_cspace_msgs/CSpace3DUpdate.h>
60 std::pair<nav_msgs::OccupancyGrid::ConstPtr,
65 const nav_msgs::OccupancyGrid::ConstPtr& msg,
68 if (map->getAngularGrid() <= 0)
71 std::runtime_error(
"ang_resolution is not set.");
87 const nav_msgs::OccupancyGrid::ConstPtr& msg,
92 auto map_msg = map->getMap();
93 if (map_msg->info.width < 1 ||
94 map_msg->info.height < 1)
97 std::pair<nav_msgs::OccupancyGrid::ConstPtr,
102 map->processMapOverlay(msg,
true);
114 const costmap_cspace_msgs::CSpace3DUpdate::Ptr& update)
123 5,
"Updated region of the costmap is empty. "
124 "The position may be out-of-boundary, or input map is wrong.");
137 sensor_msgs::PointCloud pc;
138 pc.header = map.header;
140 for (
size_t yaw = 0; yaw < map.info.angle; yaw++)
142 for (
unsigned int i = 0; i < map.info.width * map.info.height; i++)
144 int gx = i % map.info.width;
145 int gy = i / map.info.width;
146 if (map.data[i + yaw * map.info.width * map.info.height] < 100)
148 geometry_msgs::Point32 p;
149 p.x = gx * map.info.linear_resolution + map.info.origin.position.x;
150 p.y = gy * map.info.linear_resolution + map.info.origin.position.y;
152 pc.points.push_back(p);
159 auto footprint = msg;
165 const std::string overlay_mode_str)
167 if (overlay_mode_str ==
"overwrite")
171 else if (overlay_mode_str ==
"max")
175 ROS_FATAL(
"Unknown overlay_mode \"%s\"", overlay_mode_str.c_str());
176 throw std::runtime_error(
"Unknown overlay_mode.");
185 pub_costmap_ = neonavigation_common::compat::advertise<costmap_cspace_msgs::CSpace3D>(
187 pnh_,
"costmap", 1,
true);
188 pub_costmap_update_ = neonavigation_common::compat::advertise<costmap_cspace_msgs::CSpace3DUpdate>(
189 nh_,
"costmap_update",
190 pnh_,
"costmap_update", 1,
true);
195 pnh_.
param(
"ang_resolution", ang_resolution, 16);
200 ROS_FATAL(
"Footprint doesn't specified");
201 throw std::runtime_error(
"Footprint doesn't specified.");
209 catch (
const std::exception& e)
220 pnh_.
param(
"linear_expand", linear_expand, 0.2
f);
221 pnh_.
param(
"linear_spread", linear_spread, 0.5
f);
222 int linear_spread_min_cost;
223 pnh_.
param(
"linear_spread_min_cost", linear_spread_min_cost, 0);
224 root_layer->setExpansion(linear_expand, linear_spread, linear_spread_min_cost);
225 root_layer->setFootprint(footprint);
234 ROS_FATAL(
"static_layers parameter must contain at least one layer config.");
236 "Migration from old version:\n"
239 " YOUR_LAYER_NAME:\n"
240 " type: LAYER_TYPE\n"
241 " parameters: values\n"
244 " - name: YOUR_LAYER_NAME\n"
245 " type: LAYER_TYPE\n"
246 " parameters: values\n"
248 throw std::runtime_error(
"layers parameter must contain at least one layer config.");
250 for (
int i = 0; i < layers_xml.
size(); ++i)
252 auto layer_xml = std::pair<std::string, XmlRpc::XmlRpcValue>(
253 layers_xml[i][
"name"], layers_xml[i]);
254 ROS_INFO(
"New static layer: %s", layer_xml.first.c_str());
259 layer_xml.second[
"overlay_mode"]);
261 ROS_WARN(
"overlay_mode of the static layer is not specified. Using MAX mode.");
265 type = std::string(layer_xml.second[
"type"]);
268 ROS_FATAL(
"Layer type is not specified.");
269 throw std::runtime_error(
"Layer type is not specified.");
272 if (!layer_xml.second.hasMember(
"footprint"))
273 layer_xml.second[
"footprint"] = footprint_xml;
277 costmap_->addLayer(layer, overlay_mode);
278 layer->loadConfig(layer_xml.second);
300 ROS_FATAL(
"layers parameter must contain at least one layer config.");
302 "Migration from old version:\n"
305 " YOUR_LAYER_NAME:\n"
306 " type: LAYER_TYPE\n"
307 " parameters: values\n"
310 " - name: YOUR_LAYER_NAME\n"
311 " type: LAYER_TYPE\n"
312 " parameters: values\n"
314 throw std::runtime_error(
"layers parameter must contain at least one layer config.");
316 for (
int i = 0; i < layers_xml.
size(); ++i)
318 auto layer_xml = std::pair<std::string, XmlRpc::XmlRpcValue>(
319 layers_xml[i][
"name"], layers_xml[i]);
320 ROS_INFO(
"New layer: %s", layer_xml.first.c_str());
325 layer_xml.second[
"overlay_mode"]);
327 ROS_WARN(
"overlay_mode of the layer is not specified. Using MAX mode.");
331 type = std::string(layer_xml.second[
"type"]);
334 ROS_FATAL(
"Layer type is not specified.");
335 throw std::runtime_error(
"Layer type is not specified.");
338 if (!layer_xml.second.hasMember(
"footprint"))
339 layer_xml.second[
"footprint"] = footprint_xml;
343 costmap_->addLayer(layer, overlay_mode);
344 layer->loadConfig(layer_xml.second);
355 std::string overlay_mode_str;
356 pnh_.
param(
"overlay_mode", overlay_mode_str, std::string(
"max"));
357 if (overlay_mode_str.compare(
"overwrite") == 0)
359 else if (overlay_mode_str.compare(
"max") == 0)
363 ROS_FATAL(
"Unknown overlay_mode \"%s\"", overlay_mode_str.c_str());
364 throw std::runtime_error(
"Unknown overlay_mode.");
366 ROS_INFO(
"costmap_3d: %s mode", overlay_mode_str.c_str());
369 layer_xml[
"footprint"] = footprint_xml;
370 layer_xml[
"linear_expand"] = linear_expand;
371 layer_xml[
"linear_spread"] = linear_spread;
383 const geometry_msgs::PolygonStamped footprint_msg = footprint.
toMsg();
390 int main(
int argc,
char* argv[])