44 #include <tf2/convert.h>
45 #include <tf2/utils.h>
46 #include <tf2_geometry_msgs/tf2_geometry_msgs.h>
55 if (!old_h.hasParam(name))
58 XmlRpc::XmlRpcValue value;
59 old_h.getParam(name, value);
60 new_h.setParam(name, value);
61 if (should_delete) old_h.deleteParam(name);
64 Costmap2DROS::Costmap2DROS(
const std::string& name, tf2_ros::Buffer& tf) :
65 layered_costmap_(NULL),
68 transform_tolerance_(0.3),
69 map_update_thread_shutdown_(false),
73 map_update_thread_(NULL),
75 plugin_loader_(
"costmap_2d",
"costmap_2d::Layer"),
78 footprint_padding_(0.0)
81 ros::NodeHandle private_nh(
"~/" + name);
88 ros::Time last_error = ros::Time::now();
95 if (last_error + ros::Duration(5.0) < ros::Time::now())
97 ROS_WARN(
"Timed out waiting for transform from %s to %s to become available before running costmap, tf error: %s",
99 last_error = ros::Time::now();
107 bool rolling_window, track_unknown_space, always_send_full_costmap;
108 private_nh.param(
"rolling_window", rolling_window,
false);
109 private_nh.param(
"track_unknown_space", track_unknown_space,
false);
110 private_nh.param(
"always_send_full_costmap", always_send_full_costmap,
false);
114 if (!private_nh.hasParam(
"plugins"))
121 if (private_nh.hasParam(
"plugins"))
123 XmlRpc::XmlRpcValue my_list;
124 private_nh.getParam(
"plugins", my_list);
125 for (
int32_t i = 0; i < my_list.size(); ++i)
133 boost::shared_ptr<Layer> plugin =
plugin_loader_.createInstance(type);
141 if (!private_nh.searchParam(
"footprint_topic", topic_param))
143 topic_param =
"footprint_topic";
146 private_nh.param(topic_param, topic,
std::string(
"footprint"));
149 if (!private_nh.searchParam(
"published_footprint_topic", topic_param))
151 topic_param =
"published_footprint";
154 private_nh.param(topic_param, topic,
std::string(
"footprint"));
155 footprint_pub_ = private_nh.advertise<geometry_msgs::PolygonStamped>(topic, 1);
160 always_send_full_costmap);
167 dsrv_ =
new dynamic_reconfigure::Server<Costmap2DConfig>(ros::NodeHandle(
"~/" + name));
168 dynamic_reconfigure::Server<Costmap2DConfig>::CallbackType cb = [
this](
auto& config,
auto level){
reconfigureCB(config, level); };
169 dsrv_->setCallback(cb);
194 ROS_WARN(
"%s: Parameter \"plugins\" not provided, loading pre-Hydro parameters",
name_.
c_str());
199 XmlRpc::XmlRpcValue::ValueStruct
map;
203 if (nh.getParam(
"static_map", flag) && flag)
205 map[
"name"] = XmlRpc::XmlRpcValue(
"static_layer");
206 map[
"type"] = XmlRpc::XmlRpcValue(
"costmap_2d::StaticLayer");
210 ros::NodeHandle map_layer(nh,
"static_layer");
217 ros::NodeHandle obstacles(nh,
"obstacle_layer");
218 if (nh.getParam(
"map_type", s) && s ==
"voxel")
220 map[
"name"] = XmlRpc::XmlRpcValue(
"obstacle_layer");
221 map[
"type"] = XmlRpc::XmlRpcValue(
"costmap_2d::VoxelLayer");
234 map[
"name"] = XmlRpc::XmlRpcValue(
"obstacle_layer");
235 map[
"type"] = XmlRpc::XmlRpcValue(
"costmap_2d::ObstacleLayer");
244 nh.param(
"observation_sources", s,
std::string(
""));
253 ros::NodeHandle inflation(nh,
"inflation_layer");
256 map[
"name"] = XmlRpc::XmlRpcValue(
"inflation_layer");
257 map[
"type"] = XmlRpc::XmlRpcValue(
"costmap_2d::InflationLayer");
262 nh.setParam(
"plugins", super_array);
267 ros::NodeHandle target_layer(nh, plugin_name);
269 if(plugin_type ==
"costmap_2d::StaticLayer")
276 else if(plugin_type ==
"costmap_2d::VoxelLayer")
285 else if(plugin_type ==
"costmap_2d::ObstacleLayer")
292 else if(plugin_type ==
"costmap_2d::InflationLayer")
306 if(nh.hasParam(param_name)){
307 ROS_WARN(
"%s: Pre-Hydro parameter \"%s\" unused since \"plugins\" is provided",
name_.
c_str(), param_name.
c_str());
324 double map_publish_frequency = config.publish_frequency;
325 if (map_publish_frequency > 0)
331 double map_width_meters = config.width, map_height_meters = config.height, resolution = config.resolution, origin_x =
333 origin_y = config.origin_y;
338 (
unsigned int)(map_height_meters / resolution), resolution, origin_x, origin_y);
359 const costmap_2d::Costmap2DConfig &old_config)
365 if (new_config.footprint == old_config.footprint &&
366 new_config.robot_radius == old_config.robot_radius)
371 if (new_config.footprint !=
"" && new_config.footprint !=
"[]")
380 ROS_ERROR(
"Invalid footprint string from dynamic reconfigure");
404 geometry_msgs::PoseStamped new_pose;
408 ROS_WARN_THROTTLE(1.0,
"Could not get robot pose, cancelling reconfiguration");
415 ros::Rate r(frequency);
418 #ifdef HAVE_SYS_TIME_H
420 double start_t, end_t, t_diff;
421 gettimeofday(&
start, NULL);
426 #ifdef HAVE_SYS_TIME_H
427 gettimeofday(&
end, NULL);
428 start_t =
start.tv_sec + double(
start.tv_usec) / 1e6;
429 end_t =
end.tv_sec + double(
end.tv_usec) / 1e6;
430 t_diff = end_t - start_t;
431 ROS_DEBUG(
"Map update time: %.9f", t_diff);
436 unsigned int x0, y0, xn, yn;
440 ros::Time now = ros::Time::now();
449 if (r.cycleTime() > ros::Duration(1 / frequency))
450 ROS_WARN(
"Map update loop missed its desired rate of %.4fHz... the loop actually took %.4f seconds", frequency,
451 r.cycleTime().toSec());
460 geometry_msgs::PoseStamped pose;
463 double x = pose.pose.position.x,
464 y = pose.pose.position.y,
465 yaw = tf2::getYaw(pose.pose.orientation);
469 geometry_msgs::PolygonStamped footprint;
471 footprint.header.stamp = ros::Time::now();
490 (*plugin)->activate();
511 (*plugin)->deactivate();
548 tf2::toMsg(tf2::Transform::getIdentity(), global_pose.pose);
549 geometry_msgs::PoseStamped robot_pose;
550 tf2::toMsg(tf2::Transform::getIdentity(), robot_pose.pose);
552 robot_pose.header.stamp = ros::Time();
553 ros::Time current_time = ros::Time::now();
562 tf2::doTransform(robot_pose, global_pose,
transform);
570 catch (tf2::LookupException& ex)
572 ROS_ERROR_THROTTLE(1.0,
"No Transform available Error looking up robot pose: %s\n", ex.what());
575 catch (tf2::ConnectivityException& ex)
577 ROS_ERROR_THROTTLE(1.0,
"Connectivity Error looking up robot pose: %s\n", ex.what());
580 catch (tf2::ExtrapolationException& ex)
582 ROS_ERROR_THROTTLE(1.0,
"Extrapolation Error looking up robot pose: %s\n", ex.what());
586 if (!global_pose.header.stamp.isZero() && current_time.toSec() - global_pose.header.stamp.toSec() >
transform_tolerance_)
588 ROS_WARN_THROTTLE(1.0,
589 "Costmap2DROS transform timeout. Current time: %.4f, global_pose stamp: %.4f, tolerance: %.4f",
599 geometry_msgs::PoseStamped global_pose;
603 double yaw = tf2::getYaw(global_pose.pose.orientation);