62 bool track_unknown_space;
64 if (track_unknown_space)
73 double transform_tolerance;
74 nh.param(
"transform_tolerance", transform_tolerance, 0.2);
76 std::string topics_string;
78 nh.param(
"observation_sources", topics_string, std::string(
""));
79 ROS_INFO(
" Subscribed to Topics: %s", topics_string.c_str());
82 std::stringstream ss(topics_string);
90 double observation_keep_time, expected_update_rate, min_obstacle_height, max_obstacle_height;
91 std::string topic, sensor_frame, data_type;
92 bool inf_is_valid, clearing, marking;
94 source_node.
param(
"topic", topic, source);
95 source_node.
param(
"sensor_frame", sensor_frame, std::string(
""));
96 source_node.
param(
"observation_persistence", observation_keep_time, 0.0);
97 source_node.
param(
"expected_update_rate", expected_update_rate, 0.0);
98 source_node.
param(
"data_type", data_type, std::string(
"PointCloud"));
99 source_node.
param(
"min_obstacle_height", min_obstacle_height, 0.0);
100 source_node.
param(
"max_obstacle_height", max_obstacle_height, 2.0);
101 source_node.
param(
"inf_is_valid", inf_is_valid,
false);
102 source_node.
param(
"clearing", clearing,
false);
103 source_node.
param(
"marking", marking,
true);
105 if (!(data_type ==
"PointCloud2" || data_type ==
"PointCloud" || data_type ==
"LaserScan"))
107 ROS_FATAL(
"Only topics that use point clouds or laser scans are currently supported");
108 throw std::runtime_error(
"Only topics that use point clouds or laser scans are currently supported");
111 std::string raytrace_range_param_name, obstacle_range_param_name;
114 double obstacle_range = 2.5;
115 if (source_node.
searchParam(
"obstacle_range", obstacle_range_param_name))
117 source_node.
getParam(obstacle_range_param_name, obstacle_range);
121 double raytrace_range = 3.0;
122 if (source_node.
searchParam(
"raytrace_range", raytrace_range_param_name))
124 source_node.
getParam(raytrace_range_param_name, raytrace_range);
127 ROS_DEBUG(
"Creating an observation buffer for source %s, topic %s, frame %s", source.c_str(), topic.c_str(),
128 sensor_frame.c_str());
133 > (
new ObservationBuffer(topic, observation_keep_time, expected_update_rate, min_obstacle_height,
135 sensor_frame, transform_tolerance)));
146 "Created an observation buffer for source %s, topic %s, global frame: %s, "
147 "expected update rate: %.2f, observation persistence: %.2f",
148 source.c_str(), topic.c_str(),
global_frame_.c_str(), expected_update_rate, observation_keep_time);
151 if (data_type ==
"LaserScan")
161 filter->registerCallback([
this,buffer=
observation_buffers_.back()](
auto& msg){ laserScanValidInfCallback(msg, buffer); });
165 filter->registerCallback([
this,buffer=
observation_buffers_.back()](
auto& msg){ laserScanCallback(msg, buffer); });
173 else if (data_type ==
"PointCloud")
180 ROS_WARN(
"obstacle_layer: inf_is_valid option is not applicable to PointCloud observations.");
185 filter->registerCallback([
this,buffer=
observation_buffers_.back()](
auto& msg){ pointCloudCallback(msg, buffer); });
197 ROS_WARN(
"obstacle_layer: inf_is_valid option is not applicable to PointCloud observations.");
202 filter->registerCallback([
this,buffer=
observation_buffers_.back()](
auto& msg){ pointCloud2Callback(msg, buffer); });
208 if (sensor_frame !=
"")
210 std::vector < std::string > target_frames;
212 target_frames.push_back(sensor_frame);
223 dsrv_ =
new dynamic_reconfigure::Server<costmap_2d::ObstaclePluginConfig>(nh);
224 dynamic_reconfigure::Server<costmap_2d::ObstaclePluginConfig>::CallbackType cb =
225 [
this](
auto& config,
auto level){
reconfigureCB(config, level); };
226 dsrv_->setCallback(cb);
246 sensor_msgs::PointCloud2 cloud;
247 cloud.header = message->header;
256 ROS_WARN(
"High fidelity enabled, but TF returned a transform exception to frame %s: %s",
global_frame_.c_str(),
260 catch (std::runtime_error &ex)
262 ROS_WARN(
"transformLaserScanToPointCloud error, it seems the message from laser sensor is malformed. Ignore this laser scan. what(): %s", ex.what());
268 buffer->bufferCloud(cloud);
277 sensor_msgs::LaserScan message = *raw_message;
278 for (
size_t i = 0; i < message.ranges.size(); i++)
280 float range = message.ranges[ i ];
281 if (!std::isfinite(range) && range > 0)
283 message.ranges[ i ] = message.range_max -
epsilon;
288 sensor_msgs::PointCloud2 cloud;
289 cloud.header = message.header;
298 ROS_WARN(
"High fidelity enabled, but TF returned a transform exception to frame %s: %s",
302 catch (std::runtime_error &ex)
304 ROS_WARN(
"transformLaserScanToPointCloud error, it seems the message from laser sensor is malformed. Ignore this laser scan. what(): %s", ex.what());
310 buffer->bufferCloud(cloud);
317 sensor_msgs::PointCloud2 cloud2;
321 ROS_ERROR(
"Failed to convert a PointCloud to a PointCloud2, dropping message");
327 buffer->bufferCloud(cloud2);
336 buffer->bufferCloud(*message);
341 double* min_y,
double* max_x,
double* max_y)
348 std::vector<Observation> observations, clearing_observations;
360 for (
unsigned int i = 0; i < clearing_observations.size(); ++i)
366 for (std::vector<Observation>::const_iterator it = observations.begin(); it != observations.end(); ++it)
370 const sensor_msgs::PointCloud2& cloud = *(obs.
cloud_);
378 for (; iter_x !=iter_x.
end(); ++iter_x, ++iter_y, ++iter_z)
380 double px = *iter_x, py = *iter_y, pz = *iter_z;
394 if (sq_dist >= sq_obstacle_range)
404 ROS_DEBUG(
"Computing map coords failed");
408 unsigned int index =
getIndex(mx, my);
410 touch(px, py, min_x, min_y, max_x, max_y);
414 updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
418 double* max_x,
double* max_y)
476 marking_observations.insert(marking_observations.end(),
492 clearing_observations.insert(clearing_observations.end(),
498 double* max_x,
double* max_y)
500 double ox = clearing_observation.
origin_.x;
501 double oy = clearing_observation.
origin_.y;
502 const sensor_msgs::PointCloud2 &cloud = *(clearing_observation.
cloud_);
509 1.0,
"The origin for the sensor at (%.2f, %.2f) is out of map bounds. So, the costmap cannot raytrace for it.",
520 touch(ox, oy, min_x, min_y, max_x, max_y);
526 for (; iter_x != iter_x.
end(); ++iter_x, ++iter_y)
539 double t = (origin_x - ox) / a;
545 double t = (origin_y - oy) / b;
553 double t = (map_end_x - ox) / a;
554 wx = map_end_x - .001;
559 double t = (map_end_y - oy) / b;
561 wy = map_end_y - .001;
574 raytraceLine(marker, x0, y0, x1, y1, cell_raytrace_range);
605 double* min_x,
double* min_y,
double* max_x,
double* max_y)
607 double dx = wx-ox, dy = wy-oy;
608 double full_distance = hypot(dx, dy);
609 double scale = std::min(1.0, range / full_distance);
610 double ex = ox + dx * scale, ey = oy + dy * scale;
611 touch(ex, ey, min_x, min_y, max_x, max_y);