40 #include <tf2_ros/message_filter.h>
42 #include <pluginlib/class_list_macros.hpp>
43 #include <sensor_msgs/point_cloud2_iterator.h>
59 ros::NodeHandle nh(
"~/" +
name_), g_nh;
62 bool track_unknown_space;
64 if (track_unknown_space)
73 double transform_tolerance;
74 nh.param(
"transform_tolerance", transform_tolerance, 0.2);
78 nh.param(
"observation_sources", topics_string,
std::string(
""));
79 ROS_INFO(
" Subscribed to Topics: %s", topics_string.
c_str());
87 ros::NodeHandle source_node(nh, source);
90 double observation_keep_time, expected_update_rate, min_obstacle_height, max_obstacle_height;
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",
151 if (data_type ==
"LaserScan")
153 boost::shared_ptr < message_filters::Subscriber<sensor_msgs::LaserScan>
154 > sub(
new message_filters::Subscriber<sensor_msgs::LaserScan>(g_nh, topic, 50));
156 boost::shared_ptr<tf2_ros::MessageFilter<sensor_msgs::LaserScan> > filter(
157 new tf2_ros::MessageFilter<sensor_msgs::LaserScan>(*sub, *
tf_,
global_frame_, 50, g_nh));
161 filter->registerCallback([
this,buffer=
observation_buffers_.
back()](
auto& msg){ laserScanValidInfCallback(msg, buffer); });
173 else if (data_type ==
"PointCloud")
175 boost::shared_ptr < message_filters::Subscriber<sensor_msgs::PointCloud>
176 > sub(
new message_filters::Subscriber<sensor_msgs::PointCloud>(g_nh, topic, 50));
180 ROS_WARN(
"obstacle_layer: inf_is_valid option is not applicable to PointCloud observations.");
183 boost::shared_ptr < tf2_ros::MessageFilter<sensor_msgs::PointCloud>
184 > filter(
new tf2_ros::MessageFilter<sensor_msgs::PointCloud>(*sub, *
tf_,
global_frame_, 50, g_nh));
192 boost::shared_ptr < message_filters::Subscriber<sensor_msgs::PointCloud2>
193 > sub(
new message_filters::Subscriber<sensor_msgs::PointCloud2>(g_nh, topic, 50));
197 ROS_WARN(
"obstacle_layer: inf_is_valid option is not applicable to PointCloud observations.");
200 boost::shared_ptr < tf2_ros::MessageFilter<sensor_msgs::PointCloud2>
201 > filter(
new tf2_ros::MessageFilter<sensor_msgs::PointCloud2>(*sub, *
tf_,
global_frame_, 50, g_nh));
202 filter->registerCallback([
this,buffer=
observation_buffers_.
back()](
auto& msg){ pointCloud2Callback(msg, buffer); });
208 if (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);
245 const boost::shared_ptr<ObservationBuffer>& buffer)
248 sensor_msgs::PointCloud2 cloud;
249 cloud.header = message->header;
254 projector_.transformLaserScanToPointCloud(message->header.frame_id, *message, cloud, *
tf_);
256 catch (tf2::TransformException &ex)
258 ROS_WARN(
"High fidelity enabled, but TF returned a transform exception to frame %s: %s",
global_frame_.
c_str(),
264 ROS_WARN(
"transformLaserScanToPointCloud error, it seems the message from laser sensor is malformed. Ignore this laser scan. what(): %s", ex.
what());
270 buffer->bufferCloud(cloud);
275 const boost::shared_ptr<ObservationBuffer>& buffer)
278 float epsilon = 0.0001;
279 sensor_msgs::LaserScan message = *raw_message;
280 for (
size_t i = 0; i < message.ranges.size(); i++)
282 float range = message.ranges[ i ];
285 message.ranges[ i ] = message.range_max - epsilon;
290 sensor_msgs::PointCloud2 cloud;
291 cloud.header = message.header;
296 projector_.transformLaserScanToPointCloud(message.header.frame_id, message, cloud, *
tf_);
298 catch (tf2::TransformException &ex)
300 ROS_WARN(
"High fidelity enabled, but TF returned a transform exception to frame %s: %s",
306 ROS_WARN(
"transformLaserScanToPointCloud error, it seems the message from laser sensor is malformed. Ignore this laser scan. what(): %s", ex.
what());
312 buffer->bufferCloud(cloud);
317 const boost::shared_ptr<ObservationBuffer>& buffer)
319 sensor_msgs::PointCloud2 cloud2;
321 if (!sensor_msgs::convertPointCloudToPointCloud2(*message, cloud2))
323 ROS_ERROR(
"Failed to convert a PointCloud to a PointCloud2, dropping message");
329 buffer->bufferCloud(cloud2);
334 const boost::shared_ptr<ObservationBuffer>& buffer)
338 buffer->bufferCloud(*message);
352 unsigned char value =
getCost(mx, my);
356 double dt = ros::Time::now().toSec() -
getTimeStamp(mx, my);
363 touch(wx, wy, min_x, min_y, max_x, max_y);
371 double* min_y,
double* max_x,
double* max_y)
392 for (
unsigned int i = 0; i < clearing_observations.
size(); ++i)
402 const sensor_msgs::PointCloud2& cloud = *(obs.
cloud_);
406 sensor_msgs::PointCloud2ConstIterator<float> iter_x(cloud,
"x");
407 sensor_msgs::PointCloud2ConstIterator<float> iter_y(cloud,
"y");
408 sensor_msgs::PointCloud2ConstIterator<float> iter_z(cloud,
"z");
410 for (; iter_x !=iter_x.end(); ++iter_x, ++iter_y, ++iter_z)
412 double px = *iter_x, py = *iter_y, pz = *iter_z;
417 ROS_DEBUG(
"The point is too high");
426 if (sq_dist >= sq_obstacle_range)
428 ROS_DEBUG(
"The point is too far away");
436 ROS_DEBUG(
"Computing map coords failed");
441 touch(px, py, min_x, min_y, max_x, max_y);
445 updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
449 double* max_x,
double* max_y)
507 marking_observations.
insert(marking_observations.
end(),
523 clearing_observations.
insert(clearing_observations.
end(),
529 double* max_x,
double* max_y)
531 double ox = clearing_observation.
origin_.x;
532 double oy = clearing_observation.
origin_.y;
533 const sensor_msgs::PointCloud2 &cloud = *(clearing_observation.
cloud_);
540 1.0,
"The origin for the sensor at (%.2f, %.2f) is out of map bounds. So, the costmap cannot raytrace for it.",
551 touch(ox, oy, min_x, min_y, max_x, max_y);
554 sensor_msgs::PointCloud2ConstIterator<float> iter_x(cloud,
"x");
555 sensor_msgs::PointCloud2ConstIterator<float> iter_y(cloud,
"y");
557 for (; iter_x != iter_x.end(); ++iter_x, ++iter_y)
570 double t = (origin_x - ox) / a;
576 double t = (origin_y - oy) / b;
584 double t = (map_end_x - ox) / a;
585 wx = map_end_x - .001;
590 double t = (map_end_y - oy) / b;
592 wy = map_end_y - .001;
605 raytraceLine(marker, x0, y0, x1, y1, cell_raytrace_range);
636 double* min_x,
double* min_y,
double* max_x,
double* max_y)
638 double dx = wx-ox, dy = wy-oy;
639 double full_distance = hypot(dx, dy);
640 double scale =
std::min(1.0, range / full_distance);
641 double ex = ox + dx * scale, ey = oy + dy * scale;
642 touch(ex, ey, min_x, min_y, max_x, max_y);