54 void ObstacleLayer::onInitialize()
57 rolling_window_ = layered_costmap_->isRolling();
59 bool track_unknown_space;
60 nh.param(
"track_unknown_space", track_unknown_space, layered_costmap_->isTrackingUnknown());
61 if (track_unknown_space)
66 ObstacleLayer::matchSize();
69 global_frame_ = layered_costmap_->getGlobalFrameID();
70 double transform_tolerance;
71 nh.param(
"transform_tolerance", transform_tolerance, 0.2);
73 std::string topics_string;
75 nh.param(
"observation_sources", topics_string, std::string(
""));
76 ROS_INFO(
" Subscribed to Topics: %s", topics_string.c_str());
83 std::stringstream ss(topics_string);
91 double observation_keep_time, expected_update_rate, min_obstacle_height, max_obstacle_height;
92 std::string topic, sensor_frame, data_type;
93 bool inf_is_valid, clearing, marking;
95 source_node.
param(
"topic", topic, source);
96 source_node.
param(
"sensor_frame", sensor_frame, std::string(
""));
97 source_node.
param(
"observation_persistence", observation_keep_time, 0.0);
98 source_node.
param(
"expected_update_rate", expected_update_rate, 0.0);
99 source_node.
param(
"data_type", data_type, std::string(
"PointCloud"));
100 source_node.
param(
"min_obstacle_height", min_obstacle_height, 0.0);
101 source_node.
param(
"max_obstacle_height", max_obstacle_height, 2.0);
102 source_node.
param(
"inf_is_valid", inf_is_valid,
false);
103 source_node.
param(
"clearing", clearing,
false);
104 source_node.
param(
"marking", marking,
true);
106 if (!sensor_frame.empty())
108 sensor_frame =
tf::resolve(tf_prefix, sensor_frame);
111 if (!(data_type ==
"PointCloud2" || data_type ==
"PointCloud" || data_type ==
"LaserScan"))
113 ROS_FATAL(
"Only topics that use point clouds or laser scans are currently supported");
114 throw std::runtime_error(
"Only topics that use point clouds or laser scans are currently supported");
117 std::string raytrace_range_param_name, obstacle_range_param_name;
120 double obstacle_range = 2.5;
121 if (source_node.
searchParam(
"obstacle_range", obstacle_range_param_name))
123 source_node.
getParam(obstacle_range_param_name, obstacle_range);
127 double raytrace_range = 3.0;
128 if (source_node.
searchParam(
"raytrace_range", raytrace_range_param_name))
130 source_node.
getParam(raytrace_range_param_name, raytrace_range);
133 ROS_DEBUG(
"Creating an observation buffer for source %s, topic %s, frame %s", source.c_str(), topic.c_str(),
134 sensor_frame.c_str());
137 observation_buffers_.push_back(
139 > (
new ObservationBuffer(topic, observation_keep_time, expected_update_rate, min_obstacle_height,
140 max_obstacle_height, obstacle_range, raytrace_range, *
tf_, global_frame_,
141 sensor_frame, transform_tolerance)));
145 marking_buffers_.push_back(observation_buffers_.back());
149 clearing_buffers_.push_back(observation_buffers_.back());
152 "Created an observation buffer for source %s, topic %s, global frame: %s, " 153 "expected update rate: %.2f, observation persistence: %.2f",
154 source.c_str(), topic.c_str(), global_frame_.c_str(), expected_update_rate, observation_keep_time);
157 if (data_type ==
"LaserScan")
167 filter->registerCallback(
168 boost::bind(&ObstacleLayer::laserScanValidInfCallback,
this, _1, observation_buffers_.back()));
172 filter->registerCallback(
173 boost::bind(&ObstacleLayer::laserScanCallback,
this, _1, observation_buffers_.back()));
176 observation_subscribers_.push_back(sub);
177 observation_notifiers_.push_back(filter);
179 observation_notifiers_.back()->setTolerance(
ros::Duration(0.05));
181 else if (data_type ==
"PointCloud")
188 ROS_WARN(
"obstacle_layer: inf_is_valid option is not applicable to PointCloud observations.");
193 filter->registerCallback(
194 boost::bind(&ObstacleLayer::pointCloudCallback,
this, _1, observation_buffers_.back()));
196 observation_subscribers_.push_back(sub);
197 observation_notifiers_.push_back(filter);
206 ROS_WARN(
"obstacle_layer: inf_is_valid option is not applicable to PointCloud observations.");
211 filter->registerCallback(
212 boost::bind(&ObstacleLayer::pointCloud2Callback,
this, _1, observation_buffers_.back()));
214 observation_subscribers_.push_back(sub);
215 observation_notifiers_.push_back(filter);
218 if (sensor_frame !=
"")
220 std::vector < std::string > target_frames;
221 target_frames.push_back(global_frame_);
222 target_frames.push_back(sensor_frame);
223 observation_notifiers_.back()->setTargetFrames(target_frames);
228 setupDynamicReconfigure(nh);
233 dsrv_ =
new dynamic_reconfigure::Server<costmap_2d::ObstaclePluginConfig>(nh);
234 dynamic_reconfigure::Server<costmap_2d::ObstaclePluginConfig>::CallbackType cb = boost::bind(
235 &ObstacleLayer::reconfigureCB,
this, _1, _2);
236 dsrv_->setCallback(cb);
239 ObstacleLayer::~ObstacleLayer()
244 void ObstacleLayer::reconfigureCB(costmap_2d::ObstaclePluginConfig &config, uint32_t level)
246 enabled_ = config.enabled;
247 footprint_clearing_enabled_ = config.footprint_clearing_enabled;
248 max_obstacle_height_ = config.max_obstacle_height;
249 combination_method_ = config.combination_method;
252 void ObstacleLayer::laserScanCallback(
const sensor_msgs::LaserScanConstPtr& message,
256 sensor_msgs::PointCloud2 cloud;
257 cloud.header = message->header;
262 projector_.transformLaserScanToPointCloud(message->header.frame_id, *message, cloud, *
tf_);
266 ROS_WARN(
"High fidelity enabled, but TF returned a transform exception to frame %s: %s", global_frame_.c_str(),
268 projector_.projectLaser(*message, cloud);
273 buffer->bufferCloud(cloud);
277 void ObstacleLayer::laserScanValidInfCallback(
const sensor_msgs::LaserScanConstPtr& raw_message,
282 sensor_msgs::LaserScan message = *raw_message;
283 for (
size_t i = 0; i < message.ranges.size(); i++)
285 float range = message.ranges[ i ];
286 if (!std::isfinite(range) && range > 0)
288 message.ranges[ i ] = message.range_max - epsilon;
293 sensor_msgs::PointCloud2 cloud;
294 cloud.header = message.header;
299 projector_.transformLaserScanToPointCloud(message.header.frame_id, message, cloud, *
tf_);
303 ROS_WARN(
"High fidelity enabled, but TF returned a transform exception to frame %s: %s",
304 global_frame_.c_str(), ex.what());
305 projector_.projectLaser(message, cloud);
310 buffer->bufferCloud(cloud);
314 void ObstacleLayer::pointCloudCallback(
const sensor_msgs::PointCloudConstPtr& message,
317 sensor_msgs::PointCloud2 cloud2;
321 ROS_ERROR(
"Failed to convert a PointCloud to a PointCloud2, dropping message");
327 buffer->bufferCloud(cloud2);
331 void ObstacleLayer::pointCloud2Callback(
const sensor_msgs::PointCloud2ConstPtr& message,
336 buffer->bufferCloud(*message);
340 void ObstacleLayer::updateBounds(
double robot_x,
double robot_y,
double robot_yaw,
double* min_x,
341 double* min_y,
double* max_x,
double* max_y)
344 updateOrigin(robot_x - getSizeInMetersX() / 2, robot_y - getSizeInMetersY() / 2);
347 useExtraBounds(min_x, min_y, max_x, max_y);
350 std::vector<Observation> observations, clearing_observations;
353 current = current && getMarkingObservations(observations);
356 current = current && getClearingObservations(clearing_observations);
362 for (
unsigned int i = 0; i < clearing_observations.size(); ++i)
364 raytraceFreespace(clearing_observations[i], min_x, min_y, max_x, max_y);
368 for (std::vector<Observation>::const_iterator it = observations.begin(); it != observations.end(); ++it)
370 const Observation& obs = *it;
372 const pcl::PointCloud<pcl::PointXYZ>& cloud = *(obs.
cloud_);
376 for (
unsigned int i = 0; i < cloud.points.size(); ++i)
378 double px = cloud.points[i].x, py = cloud.points[i].y, pz = cloud.points[i].z;
381 if (pz > max_obstacle_height_)
392 if (sq_dist >= sq_obstacle_range)
400 if (!worldToMap(px, py, mx, my))
402 ROS_DEBUG(
"Computing map coords failed");
406 unsigned int index = getIndex(mx, my);
408 touch(px, py, min_x, min_y, max_x, max_y);
412 updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
415 void ObstacleLayer::updateFootprint(
double robot_x,
double robot_y,
double robot_yaw,
double* min_x,
double* min_y,
416 double* max_x,
double* max_y)
418 if (!footprint_clearing_enabled_)
return;
419 transformFootprint(robot_x, robot_y, robot_yaw, getFootprint(), transformed_footprint_);
421 for (
unsigned int i = 0; i < transformed_footprint_.size(); i++)
423 touch(transformed_footprint_[i].
x, transformed_footprint_[i].
y, min_x, min_y, max_x, max_y);
432 if (footprint_clearing_enabled_)
437 switch (combination_method_)
440 updateWithOverwrite(master_grid, min_i, min_j, max_i, max_j);
443 updateWithMax(master_grid, min_i, min_j, max_i, max_j);
453 static_marking_observations_.push_back(obs);
455 static_clearing_observations_.push_back(obs);
458 void ObstacleLayer::clearStaticObservations(
bool marking,
bool clearing)
461 static_marking_observations_.clear();
463 static_clearing_observations_.clear();
466 bool ObstacleLayer::getMarkingObservations(std::vector<Observation>& marking_observations)
const 470 for (
unsigned int i = 0; i < marking_buffers_.size(); ++i)
472 marking_buffers_[i]->lock();
473 marking_buffers_[i]->getObservations(marking_observations);
474 current = marking_buffers_[i]->isCurrent() && current;
475 marking_buffers_[i]->unlock();
477 marking_observations.insert(marking_observations.end(),
478 static_marking_observations_.begin(), static_marking_observations_.end());
482 bool ObstacleLayer::getClearingObservations(std::vector<Observation>& clearing_observations)
const 486 for (
unsigned int i = 0; i < clearing_buffers_.size(); ++i)
488 clearing_buffers_[i]->lock();
489 clearing_buffers_[i]->getObservations(clearing_observations);
490 current = clearing_buffers_[i]->isCurrent() && current;
491 clearing_buffers_[i]->unlock();
493 clearing_observations.insert(clearing_observations.end(),
494 static_clearing_observations_.begin(), static_clearing_observations_.end());
498 void ObstacleLayer::raytraceFreespace(
const Observation& clearing_observation,
double* min_x,
double* min_y,
499 double* max_x,
double* max_y)
501 double ox = clearing_observation.
origin_.x;
502 double oy = clearing_observation.
origin_.y;
503 pcl::PointCloud < pcl::PointXYZ > cloud = *(clearing_observation.
cloud_);
507 if (!worldToMap(ox, oy, x0, y0))
510 1.0,
"The origin for the sensor at (%.2f, %.2f) is out of map bounds. So, the costmap cannot raytrace for it.",
516 double origin_x = origin_x_, origin_y = origin_y_;
517 double map_end_x = origin_x + size_x_ * resolution_;
518 double map_end_y = origin_y + size_y_ * resolution_;
521 touch(ox, oy, min_x, min_y, max_x, max_y);
524 for (
unsigned int i = 0; i < cloud.points.size(); ++i)
526 double wx = cloud.points[i].x;
527 double wy = cloud.points[i].y;
537 double t = (origin_x - ox) / a;
543 double t = (origin_y - oy) / b;
551 double t = (map_end_x - ox) / a;
552 wx = map_end_x - .001;
557 double t = (map_end_y - oy) / b;
559 wy = map_end_y - .001;
566 if (!worldToMap(wx, wy, x1, y1))
569 unsigned int cell_raytrace_range = cellDistance(clearing_observation.
raytrace_range_);
570 MarkCell marker(costmap_, FREE_SPACE);
572 raytraceLine(marker, x0, y0, x1, y1, cell_raytrace_range);
574 updateRaytraceBounds(ox, oy, wx, wy, clearing_observation.
raytrace_range_, min_x, min_y, max_x, max_y);
578 void ObstacleLayer::activate()
581 for (
unsigned int i = 0; i < observation_subscribers_.size(); ++i)
583 if (observation_subscribers_[i] != NULL)
584 observation_subscribers_[i]->subscribe();
587 for (
unsigned int i = 0; i < observation_buffers_.size(); ++i)
589 if (observation_buffers_[i])
590 observation_buffers_[i]->resetLastUpdated();
593 void ObstacleLayer::deactivate()
595 for (
unsigned int i = 0; i < observation_subscribers_.size(); ++i)
597 if (observation_subscribers_[i] != NULL)
598 observation_subscribers_[i]->unsubscribe();
602 void ObstacleLayer::updateRaytraceBounds(
double ox,
double oy,
double wx,
double wy,
double range,
603 double* min_x,
double* min_y,
double* max_x,
double* max_y)
605 double dx = wx-ox, dy = wy-oy;
606 double full_distance = hypot(dx, dy);
607 double scale = std::min(1.0, range / full_distance);
608 double ex = ox + dx * scale, ey = oy + dy * scale;
609 touch(ex, ey, min_x, min_y, max_x, max_y);
612 void ObstacleLayer::reset()
geometry_msgs::Point origin_
std::string getPrefixParam(ros::NodeHandle &nh)
pcl::PointCloud< pcl::PointXYZ > * cloud_
PLUGINLIB_EXPORT_CLASS(BAGReader, nodelet::Nodelet)
Stores an observation in terms of a point cloud and the origin of the source.
TFSIMD_FORCE_INLINE const tfScalar & y() const
static const unsigned char FREE_SPACE
std::string resolve(const std::string &prefix, const std::string &frame_name)
Takes in point clouds from sensors, transforms them to the desired frame, and stores them...
#define ROS_WARN_THROTTLE(period,...)
bool searchParam(const std::string &key, std::string &result) const
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
TFSIMD_FORCE_INLINE const tfScalar & x() const
static bool convertPointCloudToPointCloud2(const sensor_msgs::PointCloud &input, sensor_msgs::PointCloud2 &output)
static const unsigned char LETHAL_OBSTACLE
static const unsigned char NO_INFORMATION
bool getParam(const std::string &key, std::string &s) const
A 2D costmap provides a mapping between points in the world and their associated "costs".
void transformFootprint(double x, double y, double theta, const std::vector< geometry_msgs::Point > &footprint_spec, std::vector< geometry_msgs::Point > &oriented_footprint)
Given a pose and base footprint, build the oriented footprint of the robot (list of Points) ...