costmap_3d.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2014-2018, the neonavigation authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <ros/ros.h>
31 #include <geometry_msgs/PolygonStamped.h>
32 #include <nav_msgs/OccupancyGrid.h>
33 #include <sensor_msgs/PointCloud.h>
34 
35 #include <string>
36 #include <utility>
37 #include <vector>
38 
39 #include <costmap_cspace_msgs/CSpace3D.h>
40 #include <costmap_cspace_msgs/CSpace3DUpdate.h>
41 
44 
46 {
47 protected:
51  std::vector<ros::Subscriber> sub_map_overlay_;
57 
59  std::vector<
60  std::pair<nav_msgs::OccupancyGrid::ConstPtr,
63 
64  void cbMap(
65  const nav_msgs::OccupancyGrid::ConstPtr& msg,
67  {
68  if (map->getAngularGrid() <= 0)
69  {
70  ROS_ERROR("ang_resolution is not set.");
71  std::runtime_error("ang_resolution is not set.");
72  }
73  ROS_INFO("2D costmap received");
74 
75  map->setBaseMap(msg);
76  ROS_DEBUG("C-Space costmap generated");
77 
78  if (map_buffer_.size() > 0)
79  {
80  for (auto& map : map_buffer_)
81  cbMapOverlay(map.first, map.second);
82  ROS_INFO("%ld buffered costmaps processed", map_buffer_.size());
83  map_buffer_.clear();
84  }
85  }
87  const nav_msgs::OccupancyGrid::ConstPtr& msg,
89  {
90  ROS_DEBUG("Overlay 2D costmap received");
91 
92  auto map_msg = map->getMap();
93  if (map_msg->info.width < 1 ||
94  map_msg->info.height < 1)
95  {
96  map_buffer_.push_back(
97  std::pair<nav_msgs::OccupancyGrid::ConstPtr,
99  return;
100  }
101 
102  map->processMapOverlay(msg, true);
103  ROS_DEBUG("C-Space costmap updated");
104  }
107  {
108  publishDebug(*map);
109  pub_costmap_.publish<costmap_cspace_msgs::CSpace3D>(*map);
110  return true;
111  }
112  bool cbUpdate(
114  const costmap_cspace_msgs::CSpace3DUpdate::Ptr& update)
115  {
116  if (update)
117  {
118  publishDebug(*map);
120  if (update->width * update->height * update->angle == 0)
121  {
123  5, "Updated region of the costmap is empty. "
124  "The position may be out-of-boundary, or input map is wrong.");
125  }
126  }
127  else
128  {
129  ROS_WARN_THROTTLE(5, "Failed to update the costmap.");
130  }
131  return true;
132  }
133  void publishDebug(const costmap_cspace_msgs::CSpace3D& map)
134  {
135  if (pub_debug_.getNumSubscribers() == 0)
136  return;
137  sensor_msgs::PointCloud pc;
138  pc.header = map.header;
139  pc.header.stamp = ros::Time::now();
140  for (size_t yaw = 0; yaw < map.info.angle; yaw++)
141  {
142  for (unsigned int i = 0; i < map.info.width * map.info.height; i++)
143  {
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)
147  continue;
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;
151  p.z = yaw * 0.1;
152  pc.points.push_back(p);
153  }
154  }
155  pub_debug_.publish(pc);
156  }
157  void cbPublishFootprint(const ros::TimerEvent& event, const geometry_msgs::PolygonStamped msg)
158  {
159  auto footprint = msg;
160  footprint.header.stamp = ros::Time::now();
161  pub_footprint_.publish(footprint);
162  }
163 
165  const std::string overlay_mode_str)
166  {
167  if (overlay_mode_str == "overwrite")
168  {
170  }
171  else if (overlay_mode_str == "max")
172  {
174  }
175  ROS_FATAL("Unknown overlay_mode \"%s\"", overlay_mode_str.c_str());
176  throw std::runtime_error("Unknown overlay_mode.");
177  };
178 
179 public:
181  : nh_()
182  , pnh_("~")
183  {
185  pub_costmap_ = neonavigation_common::compat::advertise<costmap_cspace_msgs::CSpace3D>(
186  nh_, "costmap",
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);
191  pub_footprint_ = pnh_.advertise<geometry_msgs::PolygonStamped>("footprint", 2, true);
192  pub_debug_ = pnh_.advertise<sensor_msgs::PointCloud>("debug", 1, true);
193 
194  int ang_resolution;
195  pnh_.param("ang_resolution", ang_resolution, 16);
196 
197  XmlRpc::XmlRpcValue footprint_xml;
198  if (!pnh_.hasParam("footprint"))
199  {
200  ROS_FATAL("Footprint doesn't specified");
201  throw std::runtime_error("Footprint doesn't specified.");
202  }
203  pnh_.getParam("footprint", footprint_xml);
204  costmap_cspace::Polygon footprint;
205  try
206  {
207  footprint = costmap_cspace::Polygon(footprint_xml);
208  }
209  catch (const std::exception& e)
210  {
211  ROS_FATAL("Invalid footprint");
212  throw e;
213  }
214 
215  costmap_.reset(new costmap_cspace::Costmap3d(ang_resolution));
216 
217  auto root_layer = costmap_->addRootLayer<costmap_cspace::Costmap3dLayerFootprint>();
218  float linear_expand;
219  float linear_spread;
220  pnh_.param("linear_expand", linear_expand, 0.2f);
221  pnh_.param("linear_spread", linear_spread, 0.5f);
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);
226 
227  if (pnh_.hasParam("static_layers"))
228  {
229  XmlRpc::XmlRpcValue layers_xml;
230  pnh_.getParam("static_layers", layers_xml);
231 
232  if (layers_xml.getType() != XmlRpc::XmlRpcValue::TypeArray || layers_xml.size() < 1)
233  {
234  ROS_FATAL("static_layers parameter must contain at least one layer config.");
235  ROS_ERROR(
236  "Migration from old version:\n"
237  "--- # Old\n"
238  "static_layers:\n"
239  " YOUR_LAYER_NAME:\n"
240  " type: LAYER_TYPE\n"
241  " parameters: values\n"
242  "--- # New\n"
243  "static_layers:\n"
244  " - name: YOUR_LAYER_NAME\n"
245  " type: LAYER_TYPE\n"
246  " parameters: values\n"
247  "---\n");
248  throw std::runtime_error("layers parameter must contain at least one layer config.");
249  }
250  for (int i = 0; i < layers_xml.size(); ++i)
251  {
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());
255 
257  if (layer_xml.second["overlay_mode"].getType() == XmlRpc::XmlRpcValue::TypeString)
258  overlay_mode = getMapOverlayModeFromString(
259  layer_xml.second["overlay_mode"]);
260  else
261  ROS_WARN("overlay_mode of the static layer is not specified. Using MAX mode.");
262 
263  std::string type;
264  if (layer_xml.second["type"].getType() == XmlRpc::XmlRpcValue::TypeString)
265  type = std::string(layer_xml.second["type"]);
266  else
267  {
268  ROS_FATAL("Layer type is not specified.");
269  throw std::runtime_error("Layer type is not specified.");
270  }
271 
272  if (!layer_xml.second.hasMember("footprint"))
273  layer_xml.second["footprint"] = footprint_xml;
274 
277  costmap_->addLayer(layer, overlay_mode);
278  layer->loadConfig(layer_xml.second);
279 
280  sub_map_overlay_.push_back(nh_.subscribe<nav_msgs::OccupancyGrid>(
281  layer_xml.first, 1,
282  boost::bind(&Costmap3DOFNode::cbMapOverlay, this, _1, layer)));
283  }
284  }
285 
286  auto static_output_layer = costmap_->addLayer<costmap_cspace::Costmap3dStaticLayerOutput>();
287  static_output_layer->setHandler(boost::bind(&Costmap3DOFNode::cbUpdateStatic, this, _1));
288 
289  sub_map_ = nh_.subscribe<nav_msgs::OccupancyGrid>(
290  "map", 1,
291  boost::bind(&Costmap3DOFNode::cbMap, this, _1, root_layer));
292 
293  if (pnh_.hasParam("layers"))
294  {
295  XmlRpc::XmlRpcValue layers_xml;
296  pnh_.getParam("layers", layers_xml);
297 
298  if (layers_xml.getType() != XmlRpc::XmlRpcValue::TypeArray || layers_xml.size() < 1)
299  {
300  ROS_FATAL("layers parameter must contain at least one layer config.");
301  ROS_ERROR(
302  "Migration from old version:\n"
303  "--- # Old\n"
304  "layers:\n"
305  " YOUR_LAYER_NAME:\n"
306  " type: LAYER_TYPE\n"
307  " parameters: values\n"
308  "--- # New\n"
309  "layers:\n"
310  " - name: YOUR_LAYER_NAME\n"
311  " type: LAYER_TYPE\n"
312  " parameters: values\n"
313  "---\n");
314  throw std::runtime_error("layers parameter must contain at least one layer config.");
315  }
316  for (int i = 0; i < layers_xml.size(); ++i)
317  {
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());
321 
323  if (layer_xml.second["overlay_mode"].getType() == XmlRpc::XmlRpcValue::TypeString)
324  overlay_mode = getMapOverlayModeFromString(
325  layer_xml.second["overlay_mode"]);
326  else
327  ROS_WARN("overlay_mode of the layer is not specified. Using MAX mode.");
328 
329  std::string type;
330  if (layer_xml.second["type"].getType() == XmlRpc::XmlRpcValue::TypeString)
331  type = std::string(layer_xml.second["type"]);
332  else
333  {
334  ROS_FATAL("Layer type is not specified.");
335  throw std::runtime_error("Layer type is not specified.");
336  }
337 
338  if (!layer_xml.second.hasMember("footprint"))
339  layer_xml.second["footprint"] = footprint_xml;
340 
343  costmap_->addLayer(layer, overlay_mode);
344  layer->loadConfig(layer_xml.second);
345 
346  sub_map_overlay_.push_back(nh_.subscribe<nav_msgs::OccupancyGrid>(
347  layer_xml.first, 1,
348  boost::bind(&Costmap3DOFNode::cbMapOverlay, this, _1, layer)));
349  }
350  }
351  else
352  {
353  // Single layer mode for backward-compatibility
354  costmap_cspace::MapOverlayMode overlay_mode;
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)
361  else
362  {
363  ROS_FATAL("Unknown overlay_mode \"%s\"", overlay_mode_str.c_str());
364  throw std::runtime_error("Unknown overlay_mode.");
365  }
366  ROS_INFO("costmap_3d: %s mode", overlay_mode_str.c_str());
367 
368  XmlRpc::XmlRpcValue layer_xml;
369  layer_xml["footprint"] = footprint_xml;
370  layer_xml["linear_expand"] = linear_expand;
371  layer_xml["linear_spread"] = linear_spread;
372 
373  auto layer = costmap_->addLayer<costmap_cspace::Costmap3dLayerFootprint>(overlay_mode);
374  layer->loadConfig(layer_xml);
375  sub_map_overlay_.push_back(nh_.subscribe<nav_msgs::OccupancyGrid>(
376  "map_overlay", 1,
377  boost::bind(&Costmap3DOFNode::cbMapOverlay, this, _1, layer)));
378  }
379 
380  auto update_output_layer = costmap_->addLayer<costmap_cspace::Costmap3dUpdateLayerOutput>();
381  update_output_layer->setHandler(boost::bind(&Costmap3DOFNode::cbUpdate, this, _1, _2));
382 
383  const geometry_msgs::PolygonStamped footprint_msg = footprint.toMsg();
385  ros::Duration(1.0),
386  boost::bind(&Costmap3DOFNode::cbPublishFootprint, this, _1, footprint_msg));
387  }
388 };
389 
390 int main(int argc, char* argv[])
391 {
392  ros::init(argc, argv, "costmap_3d");
393 
394  Costmap3DOFNode cm;
395  ros::spin();
396 
397  return 0;
398 }
XmlRpc::XmlRpcValue::size
int size() const
costmap_cspace::CSpace3DMsg::Ptr
std::shared_ptr< CSpace3DMsg > Ptr
Definition: base.h:52
Costmap3DOFNode::cbUpdateStatic
bool cbUpdateStatic(const costmap_cspace::CSpace3DMsg::Ptr &map)
Definition: costmap_3d.cpp:105
Costmap3DOFNode::sub_map_
ros::Subscriber sub_map_
Definition: costmap_3d.cpp:50
ros::Publisher
costmap_cspace::Costmap3dLayerFootprint::loadConfig
void loadConfig(XmlRpc::XmlRpcValue config)
Definition: footprint.h:84
Costmap3DOFNode::pub_debug_
ros::Publisher pub_debug_
Definition: costmap_3d.cpp:55
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
costmap_cspace::Costmap3dLayerClassLoader::loadClass
static Costmap3dLayerBase::Ptr loadClass(const std::string &name)
Definition: class_loader.h:71
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ROS_WARN_THROTTLE
#define ROS_WARN_THROTTLE(period,...)
Costmap3DOFNode::cbPublishFootprint
void cbPublishFootprint(const ros::TimerEvent &event, const geometry_msgs::PolygonStamped msg)
Definition: costmap_3d.cpp:157
ros.h
costmap_cspace::Costmap3dUpdateLayerOutput
Definition: output.h:95
Costmap3DOFNode::pnh_
ros::NodeHandle pnh_
Definition: costmap_3d.cpp:49
Costmap3DOFNode::cbUpdate
bool cbUpdate(const costmap_cspace::CSpace3DMsg::Ptr &map, const costmap_cspace_msgs::CSpace3DUpdate::Ptr &update)
Definition: costmap_3d.cpp:112
Costmap3DOFNode::pub_costmap_update_
ros::Publisher pub_costmap_update_
Definition: costmap_3d.cpp:53
Costmap3DOFNode::publishDebug
void publishDebug(const costmap_cspace_msgs::CSpace3D &map)
Definition: costmap_3d.cpp:133
compatibility.h
costmap_cspace::MapOverlayMode
MapOverlayMode
Definition: base.h:96
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
Costmap3DOFNode::costmap_
costmap_cspace::Costmap3d::Ptr costmap_
Definition: costmap_3d.cpp:58
f
f
Costmap3DOFNode
Definition: costmap_3d.cpp:45
costmap_cspace::Costmap3dLayerFootprint
Definition: footprint.h:53
costmap_cspace::OVERWRITE
@ OVERWRITE
Definition: base.h:98
update
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
ROS_DEBUG
#define ROS_DEBUG(...)
XmlRpc::XmlRpcValue::TypeString
TypeString
Costmap3DOFNode::map_buffer_
std::vector< std::pair< nav_msgs::OccupancyGrid::ConstPtr, costmap_cspace::Costmap3dLayerBase::Ptr > > map_buffer_
Definition: costmap_3d.cpp:62
Costmap3DOFNode::Costmap3DOFNode
Costmap3DOFNode()
Definition: costmap_3d.cpp:180
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
ROS_WARN
#define ROS_WARN(...)
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
ros::TimerEvent
costmap_cspace::Polygon::toMsg
geometry_msgs::PolygonStamped toMsg() const
Definition: polygon.h:123
Costmap3DOFNode::pub_footprint_
ros::Publisher pub_footprint_
Definition: costmap_3d.cpp:54
costmap_cspace::Costmap3dStaticLayerOutput
Definition: output.h:80
XmlRpc::XmlRpcValue::getType
const Type & getType() const
ROS_FATAL
#define ROS_FATAL(...)
main
int main(int argc, char *argv[])
Definition: costmap_3d.cpp:390
XmlRpc::XmlRpcValue::TypeArray
TypeArray
neonavigation_common::compat::checkCompatMode
void checkCompatMode()
Costmap3DOFNode::sub_map_overlay_
std::vector< ros::Subscriber > sub_map_overlay_
Definition: costmap_3d.cpp:51
costmap_cspace::Costmap3d
Definition: costmap_3d.h:48
costmap_cspace::Costmap3dLayerOutput::setHandler
void setHandler(CALLBACK cb)
Definition: output.h:60
costmap_3d.h
ROS_ERROR
#define ROS_ERROR(...)
Costmap3DOFNode::timer_footprint_
ros::Timer timer_footprint_
Definition: costmap_3d.cpp:56
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
Costmap3DOFNode::getMapOverlayModeFromString
static costmap_cspace::MapOverlayMode getMapOverlayModeFromString(const std::string overlay_mode_str)
Definition: costmap_3d.cpp:164
Costmap3DOFNode::cbMap
void cbMap(const nav_msgs::OccupancyGrid::ConstPtr &msg, const costmap_cspace::Costmap3dLayerBase::Ptr map)
Definition: costmap_3d.cpp:64
Costmap3DOFNode::nh_
ros::NodeHandle nh_
Definition: costmap_3d.cpp:48
ros::spin
ROSCPP_DECL void spin()
costmap_cspace::Polygon
Definition: polygon.h:90
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
costmap_cspace::MAX
@ MAX
Definition: base.h:99
Costmap3DOFNode::cbMapOverlay
void cbMapOverlay(const nav_msgs::OccupancyGrid::ConstPtr &msg, const costmap_cspace::Costmap3dLayerBase::Ptr map)
Definition: costmap_3d.cpp:86
ROS_INFO
#define ROS_INFO(...)
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
ros::Duration
ros::Timer
Costmap3DOFNode::pub_costmap_
ros::Publisher pub_costmap_
Definition: costmap_3d.cpp:52
XmlRpc::XmlRpcValue
costmap_cspace::Costmap3d::Ptr
std::shared_ptr< Costmap3d > Ptr
Definition: costmap_3d.h:55
ros::NodeHandle
ros::Subscriber
ros::Time::now
static Time now()
costmap_cspace::Costmap3dLayerBase::Ptr
std::shared_ptr< Costmap3dLayerBase > Ptr
Definition: base.h:255


costmap_cspace
Author(s): Atsushi Watanabe
autogenerated on Fri May 16 2025 02:15:10