39 #include "nav2_costmap_2d/obstacle_layer.hpp"
46 #include "pluginlib/class_list_macros.hpp"
47 #include "sensor_msgs/point_cloud2_iterator.hpp"
48 #include "nav2_costmap_2d/costmap_math.hpp"
49 #include "nav2_util/node_utils.hpp"
50 #include "rclcpp/version.h"
54 using nav2_costmap_2d::NO_INFORMATION;
55 using nav2_costmap_2d::LETHAL_OBSTACLE;
56 using nav2_costmap_2d::FREE_SPACE;
60 using rcl_interfaces::msg::ParameterType;
67 auto node = node_.lock();
79 bool track_unknown_space;
80 double transform_tolerance;
83 std::string topics_string;
86 declareParameter(
"footprint_clearing_enabled", rclcpp::ParameterValue(
true));
90 declareParameter(
"observation_sources", rclcpp::ParameterValue(std::string(
"")));
92 auto node = node_.lock();
94 throw std::runtime_error{
"Failed to lock node"};
97 node->get_parameter(name_ +
"." +
"enabled", enabled_);
98 node->get_parameter(name_ +
"." +
"footprint_clearing_enabled", footprint_clearing_enabled_);
101 node->get_parameter(
"track_unknown_space", track_unknown_space);
102 node->get_parameter(
"transform_tolerance", transform_tolerance);
103 node->get_parameter(name_ +
"." +
"observation_sources", topics_string);
104 double tf_filter_tolerance = nav2_util::declare_or_get_parameter(node, name_ +
"." +
105 "tf_filter_tolerance", 0.05);
107 int combination_method_param{};
108 node->get_parameter(name_ +
"." +
"combination_method", combination_method_param);
115 std::placeholders::_1));
119 "Subscribed to Topics: %s", topics_string.c_str());
121 rolling_window_ = layered_costmap_->
isRolling();
123 if (track_unknown_space) {
124 default_value_ = NO_INFORMATION;
126 default_value_ = FREE_SPACE;
135 auto sub_opt = rclcpp::SubscriptionOptions();
136 sub_opt.callback_group = callback_group_;
139 std::stringstream ss(topics_string);
142 while (ss >> source) {
144 double observation_keep_time, expected_update_rate, min_obstacle_height, max_obstacle_height;
145 std::string topic, sensor_frame, data_type;
146 bool inf_is_valid, clearing, marking;
149 declareParameter(source +
"." +
"sensor_frame", rclcpp::ParameterValue(std::string(
"")));
150 declareParameter(source +
"." +
"observation_persistence", rclcpp::ParameterValue(0.0));
151 declareParameter(source +
"." +
"expected_update_rate", rclcpp::ParameterValue(0.0));
152 declareParameter(source +
"." +
"data_type", rclcpp::ParameterValue(std::string(
"LaserScan")));
153 declareParameter(source +
"." +
"min_obstacle_height", rclcpp::ParameterValue(0.0));
154 declareParameter(source +
"." +
"max_obstacle_height", rclcpp::ParameterValue(0.0));
155 declareParameter(source +
"." +
"inf_is_valid", rclcpp::ParameterValue(
false));
158 declareParameter(source +
"." +
"obstacle_max_range", rclcpp::ParameterValue(2.5));
159 declareParameter(source +
"." +
"obstacle_min_range", rclcpp::ParameterValue(0.0));
160 declareParameter(source +
"." +
"raytrace_max_range", rclcpp::ParameterValue(3.0));
161 declareParameter(source +
"." +
"raytrace_min_range", rclcpp::ParameterValue(0.0));
163 node->get_parameter(name_ +
"." + source +
"." +
"topic", topic);
164 node->get_parameter(name_ +
"." + source +
"." +
"sensor_frame", sensor_frame);
166 name_ +
"." + source +
"." +
"observation_persistence",
167 observation_keep_time);
169 name_ +
"." + source +
"." +
"expected_update_rate",
170 expected_update_rate);
171 node->get_parameter(name_ +
"." + source +
"." +
"data_type", data_type);
172 node->get_parameter(name_ +
"." + source +
"." +
"min_obstacle_height", min_obstacle_height);
173 node->get_parameter(name_ +
"." + source +
"." +
"max_obstacle_height", max_obstacle_height);
174 node->get_parameter(name_ +
"." + source +
"." +
"inf_is_valid", inf_is_valid);
175 node->get_parameter(name_ +
"." + source +
"." +
"marking", marking);
176 node->get_parameter(name_ +
"." + source +
"." +
"clearing", clearing);
178 if (!(data_type ==
"PointCloud2" || data_type ==
"LaserScan")) {
181 "Only topics that use point cloud2s or laser scans are currently supported");
182 throw std::runtime_error(
183 "Only topics that use point cloud2s or laser scans are currently supported");
187 double obstacle_max_range, obstacle_min_range;
188 node->get_parameter(name_ +
"." + source +
"." +
"obstacle_max_range", obstacle_max_range);
189 node->get_parameter(name_ +
"." + source +
"." +
"obstacle_min_range", obstacle_min_range);
192 double raytrace_max_range, raytrace_min_range;
193 node->get_parameter(name_ +
"." + source +
"." +
"raytrace_min_range", raytrace_min_range);
194 node->get_parameter(name_ +
"." + source +
"." +
"raytrace_max_range", raytrace_max_range);
200 "Creating an observation buffer for source %s, topic %s, frame %s",
201 source.c_str(), topic.c_str(),
202 sensor_frame.c_str());
209 node, topic, observation_keep_time, expected_update_rate,
211 max_obstacle_height, obstacle_max_range, obstacle_min_range, raytrace_max_range,
212 raytrace_min_range, *tf_,
214 sensor_frame, tf2::durationFromSec(transform_tolerance))));
228 "Created an observation buffer for source %s, topic %s, global frame: %s, "
229 "expected update rate: %.2f, observation persistence: %.2f",
230 source.c_str(), topic.c_str(),
231 global_frame_.c_str(), expected_update_rate, observation_keep_time);
233 const auto custom_qos_profile = rclcpp::SensorDataQoS().keep_last(50);
236 if (data_type ==
"LaserScan") {
237 std::shared_ptr<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
238 rclcpp_lifecycle::LifecycleNode>> sub;
241 #if RCLCPP_VERSION_GTE(29, 0, 0)
242 sub = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
243 rclcpp_lifecycle::LifecycleNode>>(node, topic, custom_qos_profile, sub_opt);
245 sub = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
246 rclcpp_lifecycle::LifecycleNode>>(
247 node, topic, custom_qos_profile.get_rmw_qos_profile(), sub_opt);
252 auto filter = std::make_shared<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>>(
254 node->get_node_logging_interface(),
255 node->get_node_clock_interface(),
256 tf2::durationFromSec(transform_tolerance));
259 filter->registerCallback(
265 filter->registerCallback(
275 tf_filter_tolerance));
278 std::shared_ptr<message_filters::Subscriber<sensor_msgs::msg::PointCloud2,
279 rclcpp_lifecycle::LifecycleNode>> sub;
282 #if RCLCPP_VERSION_GTE(29, 0, 0)
283 sub = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::PointCloud2,
284 rclcpp_lifecycle::LifecycleNode>>(node, topic, custom_qos_profile, sub_opt);
286 sub = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::PointCloud2,
287 rclcpp_lifecycle::LifecycleNode>>(
288 node, topic, custom_qos_profile.get_rmw_qos_profile(), sub_opt);
296 "obstacle_layer: inf_is_valid option is not applicable to PointCloud observations.");
299 auto filter = std::make_shared<tf2_ros::MessageFilter<sensor_msgs::msg::PointCloud2>>(
301 node->get_node_logging_interface(),
302 node->get_node_clock_interface(),
303 tf2::durationFromSec(transform_tolerance));
305 filter->registerCallback(
314 if (sensor_frame !=
"") {
315 std::vector<std::string> target_frames;
317 target_frames.push_back(sensor_frame);
323 rcl_interfaces::msg::SetParametersResult
325 std::vector<rclcpp::Parameter> parameters)
327 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
328 rcl_interfaces::msg::SetParametersResult result;
330 for (
auto parameter : parameters) {
331 const auto & param_type = parameter.get_type();
332 const auto & param_name = parameter.get_name();
333 if (param_name.find(name_ +
".") != 0) {
337 if (param_type == ParameterType::PARAMETER_DOUBLE) {
338 if (param_name == name_ +
"." +
"min_obstacle_height") {
340 }
else if (param_name == name_ +
"." +
"max_obstacle_height") {
343 }
else if (param_type == ParameterType::PARAMETER_BOOL) {
344 if (param_name == name_ +
"." +
"enabled" && enabled_ != parameter.as_bool()) {
345 enabled_ = parameter.as_bool();
349 }
else if (param_name == name_ +
"." +
"footprint_clearing_enabled") {
350 footprint_clearing_enabled_ = parameter.as_bool();
352 }
else if (param_type == ParameterType::PARAMETER_INTEGER) {
353 if (param_name == name_ +
"." +
"combination_method") {
359 result.successful =
true;
365 sensor_msgs::msg::LaserScan::ConstSharedPtr message,
366 const std::shared_ptr<nav2_costmap_2d::ObservationBuffer> & buffer)
369 sensor_msgs::msg::PointCloud2 cloud;
370 cloud.header = message->header;
374 projector_.transformLaserScanToPointCloud(message->header.frame_id, *message, cloud, *tf_);
375 }
catch (tf2::TransformException & ex) {
378 "High fidelity enabled, but TF returned a transform exception to frame %s: %s",
382 }
catch (std::runtime_error & ex) {
385 "transformLaserScanToPointCloud error, it seems the message from laser is malformed."
386 " Ignore this message. what(): %s",
393 buffer->bufferCloud(cloud);
399 sensor_msgs::msg::LaserScan::ConstSharedPtr raw_message,
400 const std::shared_ptr<nav2_costmap_2d::ObservationBuffer> & buffer)
403 float epsilon = 0.0001;
404 sensor_msgs::msg::LaserScan message = *raw_message;
405 for (
size_t i = 0; i < message.ranges.size(); i++) {
406 float range = message.ranges[i];
407 if (!std::isfinite(range) && range > 0) {
408 message.ranges[i] = message.range_max - epsilon;
413 sensor_msgs::msg::PointCloud2 cloud;
414 cloud.header = message.header;
418 projector_.transformLaserScanToPointCloud(message.header.frame_id, message, cloud, *tf_);
419 }
catch (tf2::TransformException & ex) {
422 "High fidelity enabled, but TF returned a transform exception to frame %s: %s",
425 }
catch (std::runtime_error & ex) {
428 "transformLaserScanToPointCloud error, it seems the message from laser is malformed."
429 " Ignore this message. what(): %s",
436 buffer->bufferCloud(cloud);
442 sensor_msgs::msg::PointCloud2::ConstSharedPtr message,
443 const std::shared_ptr<ObservationBuffer> & buffer)
447 buffer->bufferCloud(*message);
453 double robot_x,
double robot_y,
double robot_yaw,
double * min_x,
454 double * min_y,
double * max_x,
double * max_y)
456 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
457 if (rolling_window_) {
463 useExtraBounds(min_x, min_y, max_x, max_y);
466 std::vector<Observation> observations, clearing_observations;
478 for (
unsigned int i = 0; i < clearing_observations.size(); ++i) {
483 for (std::vector<Observation>::const_iterator it = observations.begin();
484 it != observations.end(); ++it)
488 const sensor_msgs::msg::PointCloud2 & cloud = *(obs.cloud_);
490 double sq_obstacle_max_range = obs.obstacle_max_range_ * obs.obstacle_max_range_;
491 double sq_obstacle_min_range = obs.obstacle_min_range_ * obs.obstacle_min_range_;
493 sensor_msgs::PointCloud2ConstIterator<float> iter_x(cloud,
"x");
494 sensor_msgs::PointCloud2ConstIterator<float> iter_y(cloud,
"y");
495 sensor_msgs::PointCloud2ConstIterator<float> iter_z(cloud,
"z");
497 for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) {
498 double px = *iter_x, py = *iter_y, pz = *iter_z;
502 RCLCPP_DEBUG(logger_,
"The point is too low");
508 RCLCPP_DEBUG(logger_,
"The point is too high");
515 obs.origin_.x) * (px - obs.origin_.x) + (py - obs.origin_.y) * (py - obs.origin_.y) +
516 (pz - obs.origin_.z) * (pz - obs.origin_.z);
519 if (sq_dist >= sq_obstacle_max_range) {
520 RCLCPP_DEBUG(logger_,
"The point is too far away");
525 if (sq_dist < sq_obstacle_min_range) {
526 RCLCPP_DEBUG(logger_,
"The point is too close");
533 RCLCPP_DEBUG(logger_,
"Computing map coords failed");
537 unsigned int index =
getIndex(mx, my);
538 costmap_[index] = LETHAL_OBSTACLE;
539 touch(px, py, min_x, min_y, max_x, max_y);
543 updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
548 double robot_x,
double robot_y,
double robot_yaw,
549 double * min_x,
double * min_y,
553 if (!footprint_clearing_enabled_) {
return;}
556 for (
unsigned int i = 0; i < transformed_footprint_.size(); i++) {
557 touch(transformed_footprint_[i].x, transformed_footprint_[i].y, min_x, min_y, max_x, max_y);
567 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
573 if (!current_ && was_reset_) {
578 if (footprint_clearing_enabled_) {
582 switch (combination_method_) {
584 updateWithOverwrite(master_grid, min_i, min_j, max_i, max_j);
587 updateWithMax(master_grid, min_i, min_j, max_i, max_j);
590 updateWithMaxWithoutUnknownOverwrite(master_grid, min_i, min_j, max_i, max_j);
598 ObstacleLayer::addStaticObservation(
600 bool marking,
bool clearing)
603 static_marking_observations_.push_back(obs);
606 static_clearing_observations_.push_back(obs);
611 ObstacleLayer::clearStaticObservations(
bool marking,
bool clearing)
614 static_marking_observations_.clear();
617 static_clearing_observations_.clear();
632 marking_observations.insert(
633 marking_observations.end(),
634 static_marking_observations_.begin(), static_marking_observations_.end());
649 clearing_observations.insert(
650 clearing_observations.end(),
651 static_clearing_observations_.begin(), static_clearing_observations_.end());
657 const Observation & clearing_observation,
double * min_x,
662 double ox = clearing_observation.origin_.x;
663 double oy = clearing_observation.origin_.y;
664 const sensor_msgs::msg::PointCloud2 & cloud = *(clearing_observation.cloud_);
671 "Sensor origin at (%.2f, %.2f) is out of map bounds (%.2f, %.2f) to (%.2f, %.2f). "
672 "The costmap cannot raytrace for it.",
674 origin_x_, origin_y_,
680 double origin_x = origin_x_, origin_y = origin_y_;
681 double map_end_x = origin_x + size_x_ * resolution_;
682 double map_end_y = origin_y + size_y_ * resolution_;
685 touch(ox, oy, min_x, min_y, max_x, max_y);
689 sensor_msgs::PointCloud2ConstIterator<float> iter_x(cloud,
"x");
690 sensor_msgs::PointCloud2ConstIterator<float> iter_y(cloud,
"y");
692 for (; iter_x != iter_x.end(); ++iter_x, ++iter_y) {
703 double t = (origin_x - ox) / a;
708 double t = (origin_y - oy) / b;
714 if (wx > map_end_x) {
715 double t = (map_end_x - ox) / a;
716 wx = map_end_x - .001;
719 if (wy > map_end_y) {
720 double t = (map_end_y - oy) / b;
722 wy = map_end_y - .001;
733 unsigned int cell_raytrace_max_range =
cellDistance(clearing_observation.raytrace_max_range_);
734 unsigned int cell_raytrace_min_range =
cellDistance(clearing_observation.raytrace_min_range_);
735 MarkCell marker(costmap_, FREE_SPACE);
737 raytraceLine(marker, x0, y0, x1, y1, cell_raytrace_max_range, cell_raytrace_min_range);
740 ox, oy, wx, wy, clearing_observation.raytrace_max_range_,
741 clearing_observation.raytrace_min_range_, min_x, min_y, max_x,
774 double ox,
double oy,
double wx,
double wy,
double max_range,
double min_range,
775 double * min_x,
double * min_y,
double * max_x,
double * max_y)
777 double dx = wx - ox, dy = wy - oy;
778 double full_distance = hypot(dx, dy);
779 if (full_distance < min_range) {
782 double scale = std::min(1.0, max_range / full_distance);
783 double ex = ox + dx * scale, ey = oy + dy * scale;
784 touch(ex, ey, min_x, min_y, max_x, max_y);
A 2D costmap provides a mapping between points in the world and their associated "costs".
unsigned int getIndex(unsigned int mx, unsigned int my) const
Given two map coordinates... compute the associated index.
void raytraceLine(ActionType at, unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, unsigned int max_length=UINT_MAX, unsigned int min_length=0)
Raytrace a line and apply some action at each step.
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates.
virtual void updateOrigin(double new_origin_x, double new_origin_y)
Move the origin of the costmap to a new location.... keeping data when it can.
bool setConvexPolygonCost(const std::vector< geometry_msgs::msg::Point > &polygon, unsigned char cost_value)
Sets the cost of a convex polygon to a desired value.
double getSizeInMetersY() const
Accessor for the y size of the costmap in meters.
double getSizeInMetersX() const
Accessor for the x size of the costmap in meters.
virtual void resetMaps()
Resets the costmap and static_map to be unknown space.
unsigned int cellDistance(double world_dist)
Given distance in the world... convert it to cells.
void touch(double x, double y, double *min_x, double *min_y, double *max_x, double *max_y)
virtual void matchSize()
Match the size of the master costmap.
CombinationMethod combination_method_from_int(const int value)
Converts an integer to a CombinationMethod enum and logs on failure.
Abstract class for layered costmap plugin implementations.
std::string joinWithParentNamespace(const std::string &topic)
void declareParameter(const std::string ¶m_name, const rclcpp::ParameterValue &value)
Convenience functions for declaring ROS parameters.
const std::vector< geometry_msgs::msg::Point > & getFootprint() const
Convenience function for layered_costmap_->getFootprint().
bool isRolling()
If this costmap is rolling or not.
Takes in point clouds from sensors, transforms them to the desired frame, and stores them.
Stores an observation in terms of a point cloud and the origin of the source.
Takes in laser and pointcloud data to populate into 2D costmap.
void pointCloud2Callback(sensor_msgs::msg::PointCloud2::ConstSharedPtr message, const std::shared_ptr< nav2_costmap_2d::ObservationBuffer > &buffer)
A callback to handle buffering PointCloud2 messages.
std::vector< std::shared_ptr< nav2_costmap_2d::ObservationBuffer > > marking_buffers_
Used to store observation buffers used for marking obstacles.
virtual void activate()
Activate the layer.
std::vector< std::shared_ptr< tf2_ros::MessageFilterBase > > observation_notifiers_
Used to make sure that transforms are available for each sensor.
bool getMarkingObservations(std::vector< nav2_costmap_2d::Observation > &marking_observations) const
Get the observations used to mark space.
std::string global_frame_
The global frame for the costmap.
bool getClearingObservations(std::vector< nav2_costmap_2d::Observation > &clearing_observations) const
Get the observations used to clear space.
void updateRaytraceBounds(double ox, double oy, double wx, double wy, double max_range, double min_range, double *min_x, double *min_y, double *max_x, double *max_y)
Process update costmap with raytracing the window bounds.
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_
Dynamic parameters handler.
void laserScanCallback(sensor_msgs::msg::LaserScan::ConstSharedPtr message, const std::shared_ptr< nav2_costmap_2d::ObservationBuffer > &buffer)
A callback to handle buffering LaserScan messages.
void resetBuffersLastUpdated()
triggers the update of observations buffer
std::vector< std::shared_ptr< nav2_costmap_2d::ObservationBuffer > > clearing_buffers_
Used to store observation buffers used for clearing obstacles.
void laserScanValidInfCallback(sensor_msgs::msg::LaserScan::ConstSharedPtr message, const std::shared_ptr< nav2_costmap_2d::ObservationBuffer > &buffer)
A callback to handle buffering LaserScan messages which need filtering to turn Inf values into range_...
std::vector< std::shared_ptr< message_filters::SubscriberBase< rclcpp_lifecycle::LifecycleNode > > > observation_subscribers_
Used for the observation message filters.
void updateFootprint(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
Clear costmap layer info below the robot's footprint.
virtual void deactivate()
Deactivate the layer.
virtual void updateCosts(nav2_costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
Update the costs in the master costmap in the window.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
virtual ~ObstacleLayer()
A destructor.
std::vector< std::shared_ptr< nav2_costmap_2d::ObservationBuffer > > observation_buffers_
Used to store observations from various sensors.
virtual void onInitialize()
Initialization process of layer on startup.
double min_obstacle_height_
Max Obstacle Height.
laser_geometry::LaserProjection projector_
Used to project laser scans into point clouds.
double max_obstacle_height_
Max Obstacle Height.
virtual void reset()
Reset this costmap.
virtual void raytraceFreespace(const nav2_costmap_2d::Observation &clearing_observation, double *min_x, double *min_y, double *max_x, double *max_y)
Clear freespace based on one observation.
virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
Update the bounds of the master costmap by this layer's update dimensions.
void transformFootprint(double x, double y, double theta, const std::vector< geometry_msgs::msg::Point > &footprint_spec, std::vector< geometry_msgs::msg::Point > &oriented_footprint)
Given a pose and base footprint, build the oriented footprint of the robot (list of Points)
@ MaxWithoutUnknownOverwrite