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 "rclcpp/version.h"
53 using nav2_costmap_2d::NO_INFORMATION;
54 using nav2_costmap_2d::LETHAL_OBSTACLE;
55 using nav2_costmap_2d::FREE_SPACE;
59 using rcl_interfaces::msg::ParameterType;
66 auto node = node_.lock();
78 bool track_unknown_space;
79 double transform_tolerance;
82 std::string topics_string;
85 declareParameter(
"footprint_clearing_enabled", rclcpp::ParameterValue(
true));
89 declareParameter(
"observation_sources", rclcpp::ParameterValue(std::string(
"")));
91 auto node = node_.lock();
93 throw std::runtime_error{
"Failed to lock node"};
96 node->get_parameter(name_ +
"." +
"enabled", enabled_);
97 node->get_parameter(name_ +
"." +
"footprint_clearing_enabled", footprint_clearing_enabled_);
100 node->get_parameter(
"track_unknown_space", track_unknown_space);
101 node->get_parameter(
"transform_tolerance", transform_tolerance);
102 node->get_parameter(name_ +
"." +
"observation_sources", topics_string);
104 int combination_method_param{};
105 node->get_parameter(name_ +
"." +
"combination_method", combination_method_param);
112 std::placeholders::_1));
116 "Subscribed to Topics: %s", topics_string.c_str());
118 rolling_window_ = layered_costmap_->
isRolling();
120 if (track_unknown_space) {
121 default_value_ = NO_INFORMATION;
123 default_value_ = FREE_SPACE;
132 auto sub_opt = rclcpp::SubscriptionOptions();
133 sub_opt.callback_group = callback_group_;
136 std::stringstream ss(topics_string);
139 while (ss >> source) {
141 double observation_keep_time, expected_update_rate, min_obstacle_height, max_obstacle_height;
142 std::string topic, sensor_frame, data_type;
143 bool inf_is_valid, clearing, marking;
146 declareParameter(source +
"." +
"sensor_frame", rclcpp::ParameterValue(std::string(
"")));
147 declareParameter(source +
"." +
"observation_persistence", rclcpp::ParameterValue(0.0));
148 declareParameter(source +
"." +
"expected_update_rate", rclcpp::ParameterValue(0.0));
149 declareParameter(source +
"." +
"data_type", rclcpp::ParameterValue(std::string(
"LaserScan")));
150 declareParameter(source +
"." +
"min_obstacle_height", rclcpp::ParameterValue(0.0));
151 declareParameter(source +
"." +
"max_obstacle_height", rclcpp::ParameterValue(0.0));
152 declareParameter(source +
"." +
"inf_is_valid", rclcpp::ParameterValue(
false));
155 declareParameter(source +
"." +
"obstacle_max_range", rclcpp::ParameterValue(2.5));
156 declareParameter(source +
"." +
"obstacle_min_range", rclcpp::ParameterValue(0.0));
157 declareParameter(source +
"." +
"raytrace_max_range", rclcpp::ParameterValue(3.0));
158 declareParameter(source +
"." +
"raytrace_min_range", rclcpp::ParameterValue(0.0));
160 node->get_parameter(name_ +
"." + source +
"." +
"topic", topic);
161 node->get_parameter(name_ +
"." + source +
"." +
"sensor_frame", sensor_frame);
163 name_ +
"." + source +
"." +
"observation_persistence",
164 observation_keep_time);
166 name_ +
"." + source +
"." +
"expected_update_rate",
167 expected_update_rate);
168 node->get_parameter(name_ +
"." + source +
"." +
"data_type", data_type);
169 node->get_parameter(name_ +
"." + source +
"." +
"min_obstacle_height", min_obstacle_height);
170 node->get_parameter(name_ +
"." + source +
"." +
"max_obstacle_height", max_obstacle_height);
171 node->get_parameter(name_ +
"." + source +
"." +
"inf_is_valid", inf_is_valid);
172 node->get_parameter(name_ +
"." + source +
"." +
"marking", marking);
173 node->get_parameter(name_ +
"." + source +
"." +
"clearing", clearing);
175 if (!(data_type ==
"PointCloud2" || data_type ==
"LaserScan")) {
178 "Only topics that use point cloud2s or laser scans are currently supported");
179 throw std::runtime_error(
180 "Only topics that use point cloud2s or laser scans are currently supported");
184 double obstacle_max_range, obstacle_min_range;
185 node->get_parameter(name_ +
"." + source +
"." +
"obstacle_max_range", obstacle_max_range);
186 node->get_parameter(name_ +
"." + source +
"." +
"obstacle_min_range", obstacle_min_range);
189 double raytrace_max_range, raytrace_min_range;
190 node->get_parameter(name_ +
"." + source +
"." +
"raytrace_min_range", raytrace_min_range);
191 node->get_parameter(name_ +
"." + source +
"." +
"raytrace_max_range", raytrace_max_range);
197 "Creating an observation buffer for source %s, topic %s, frame %s",
198 source.c_str(), topic.c_str(),
199 sensor_frame.c_str());
206 node, topic, observation_keep_time, expected_update_rate,
208 max_obstacle_height, obstacle_max_range, obstacle_min_range, raytrace_max_range,
209 raytrace_min_range, *tf_,
211 sensor_frame, tf2::durationFromSec(transform_tolerance))));
225 "Created an observation buffer for source %s, topic %s, global frame: %s, "
226 "expected update rate: %.2f, observation persistence: %.2f",
227 source.c_str(), topic.c_str(),
228 global_frame_.c_str(), expected_update_rate, observation_keep_time);
230 const auto custom_qos_profile = rclcpp::SensorDataQoS().keep_last(50);
233 if (data_type ==
"LaserScan") {
234 std::shared_ptr<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
235 rclcpp_lifecycle::LifecycleNode>> sub;
238 #if RCLCPP_VERSION_GTE(29, 0, 0)
239 sub = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
240 rclcpp_lifecycle::LifecycleNode>>(node, topic, custom_qos_profile, sub_opt);
242 sub = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
243 rclcpp_lifecycle::LifecycleNode>>(
244 node, topic, custom_qos_profile.get_rmw_qos_profile(), sub_opt);
249 auto filter = std::make_shared<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>>(
251 node->get_node_logging_interface(),
252 node->get_node_clock_interface(),
253 tf2::durationFromSec(transform_tolerance));
256 filter->registerCallback(
262 filter->registerCallback(
274 std::shared_ptr<message_filters::Subscriber<sensor_msgs::msg::PointCloud2,
275 rclcpp_lifecycle::LifecycleNode>> sub;
278 #if RCLCPP_VERSION_GTE(29, 0, 0)
279 sub = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::PointCloud2,
280 rclcpp_lifecycle::LifecycleNode>>(node, topic, custom_qos_profile, sub_opt);
282 sub = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::PointCloud2,
283 rclcpp_lifecycle::LifecycleNode>>(
284 node, topic, custom_qos_profile.get_rmw_qos_profile(), sub_opt);
292 "obstacle_layer: inf_is_valid option is not applicable to PointCloud observations.");
295 auto filter = std::make_shared<tf2_ros::MessageFilter<sensor_msgs::msg::PointCloud2>>(
297 node->get_node_logging_interface(),
298 node->get_node_clock_interface(),
299 tf2::durationFromSec(transform_tolerance));
301 filter->registerCallback(
310 if (sensor_frame !=
"") {
311 std::vector<std::string> target_frames;
313 target_frames.push_back(sensor_frame);
319 rcl_interfaces::msg::SetParametersResult
321 std::vector<rclcpp::Parameter> parameters)
323 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
324 rcl_interfaces::msg::SetParametersResult result;
326 for (
auto parameter : parameters) {
327 const auto & param_type = parameter.get_type();
328 const auto & param_name = parameter.get_name();
329 if (param_name.find(name_ +
".") != 0) {
333 if (param_type == ParameterType::PARAMETER_DOUBLE) {
334 if (param_name == name_ +
"." +
"min_obstacle_height") {
336 }
else if (param_name == name_ +
"." +
"max_obstacle_height") {
339 }
else if (param_type == ParameterType::PARAMETER_BOOL) {
340 if (param_name == name_ +
"." +
"enabled" && enabled_ != parameter.as_bool()) {
341 enabled_ = parameter.as_bool();
345 }
else if (param_name == name_ +
"." +
"footprint_clearing_enabled") {
346 footprint_clearing_enabled_ = parameter.as_bool();
348 }
else if (param_type == ParameterType::PARAMETER_INTEGER) {
349 if (param_name == name_ +
"." +
"combination_method") {
355 result.successful =
true;
361 sensor_msgs::msg::LaserScan::ConstSharedPtr message,
362 const std::shared_ptr<nav2_costmap_2d::ObservationBuffer> & buffer)
365 sensor_msgs::msg::PointCloud2 cloud;
366 cloud.header = message->header;
370 projector_.transformLaserScanToPointCloud(message->header.frame_id, *message, cloud, *tf_);
371 }
catch (tf2::TransformException & ex) {
374 "High fidelity enabled, but TF returned a transform exception to frame %s: %s",
378 }
catch (std::runtime_error & ex) {
381 "transformLaserScanToPointCloud error, it seems the message from laser is malformed."
382 " Ignore this message. what(): %s",
389 buffer->bufferCloud(cloud);
395 sensor_msgs::msg::LaserScan::ConstSharedPtr raw_message,
396 const std::shared_ptr<nav2_costmap_2d::ObservationBuffer> & buffer)
399 float epsilon = 0.0001;
400 sensor_msgs::msg::LaserScan message = *raw_message;
401 for (
size_t i = 0; i < message.ranges.size(); i++) {
402 float range = message.ranges[i];
403 if (!std::isfinite(range) && range > 0) {
404 message.ranges[i] = message.range_max - epsilon;
409 sensor_msgs::msg::PointCloud2 cloud;
410 cloud.header = message.header;
414 projector_.transformLaserScanToPointCloud(message.header.frame_id, message, cloud, *tf_);
415 }
catch (tf2::TransformException & ex) {
418 "High fidelity enabled, but TF returned a transform exception to frame %s: %s",
421 }
catch (std::runtime_error & ex) {
424 "transformLaserScanToPointCloud error, it seems the message from laser is malformed."
425 " Ignore this message. what(): %s",
432 buffer->bufferCloud(cloud);
438 sensor_msgs::msg::PointCloud2::ConstSharedPtr message,
439 const std::shared_ptr<ObservationBuffer> & buffer)
443 buffer->bufferCloud(*message);
449 double robot_x,
double robot_y,
double robot_yaw,
double * min_x,
450 double * min_y,
double * max_x,
double * max_y)
452 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
453 if (rolling_window_) {
459 useExtraBounds(min_x, min_y, max_x, max_y);
462 std::vector<Observation> observations, clearing_observations;
474 for (
unsigned int i = 0; i < clearing_observations.size(); ++i) {
479 for (std::vector<Observation>::const_iterator it = observations.begin();
480 it != observations.end(); ++it)
484 const sensor_msgs::msg::PointCloud2 & cloud = *(obs.cloud_);
486 double sq_obstacle_max_range = obs.obstacle_max_range_ * obs.obstacle_max_range_;
487 double sq_obstacle_min_range = obs.obstacle_min_range_ * obs.obstacle_min_range_;
489 sensor_msgs::PointCloud2ConstIterator<float> iter_x(cloud,
"x");
490 sensor_msgs::PointCloud2ConstIterator<float> iter_y(cloud,
"y");
491 sensor_msgs::PointCloud2ConstIterator<float> iter_z(cloud,
"z");
493 for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) {
494 double px = *iter_x, py = *iter_y, pz = *iter_z;
498 RCLCPP_DEBUG(logger_,
"The point is too low");
504 RCLCPP_DEBUG(logger_,
"The point is too high");
511 obs.origin_.x) * (px - obs.origin_.x) + (py - obs.origin_.y) * (py - obs.origin_.y) +
512 (pz - obs.origin_.z) * (pz - obs.origin_.z);
515 if (sq_dist >= sq_obstacle_max_range) {
516 RCLCPP_DEBUG(logger_,
"The point is too far away");
521 if (sq_dist < sq_obstacle_min_range) {
522 RCLCPP_DEBUG(logger_,
"The point is too close");
529 RCLCPP_DEBUG(logger_,
"Computing map coords failed");
533 unsigned int index =
getIndex(mx, my);
534 costmap_[index] = LETHAL_OBSTACLE;
535 touch(px, py, min_x, min_y, max_x, max_y);
539 updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
544 double robot_x,
double robot_y,
double robot_yaw,
545 double * min_x,
double * min_y,
549 if (!footprint_clearing_enabled_) {
return;}
552 for (
unsigned int i = 0; i < transformed_footprint_.size(); i++) {
553 touch(transformed_footprint_[i].x, transformed_footprint_[i].y, min_x, min_y, max_x, max_y);
563 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
569 if (!current_ && was_reset_) {
574 if (footprint_clearing_enabled_) {
578 switch (combination_method_) {
580 updateWithOverwrite(master_grid, min_i, min_j, max_i, max_j);
583 updateWithMax(master_grid, min_i, min_j, max_i, max_j);
586 updateWithMaxWithoutUnknownOverwrite(master_grid, min_i, min_j, max_i, max_j);
594 ObstacleLayer::addStaticObservation(
596 bool marking,
bool clearing)
599 static_marking_observations_.push_back(obs);
602 static_clearing_observations_.push_back(obs);
607 ObstacleLayer::clearStaticObservations(
bool marking,
bool clearing)
610 static_marking_observations_.clear();
613 static_clearing_observations_.clear();
628 marking_observations.insert(
629 marking_observations.end(),
630 static_marking_observations_.begin(), static_marking_observations_.end());
645 clearing_observations.insert(
646 clearing_observations.end(),
647 static_clearing_observations_.begin(), static_clearing_observations_.end());
653 const Observation & clearing_observation,
double * min_x,
658 double ox = clearing_observation.origin_.x;
659 double oy = clearing_observation.origin_.y;
660 const sensor_msgs::msg::PointCloud2 & cloud = *(clearing_observation.cloud_);
667 "Sensor origin at (%.2f, %.2f) is out of map bounds (%.2f, %.2f) to (%.2f, %.2f). "
668 "The costmap cannot raytrace for it.",
670 origin_x_, origin_y_,
676 double origin_x = origin_x_, origin_y = origin_y_;
677 double map_end_x = origin_x + size_x_ * resolution_;
678 double map_end_y = origin_y + size_y_ * resolution_;
681 touch(ox, oy, min_x, min_y, max_x, max_y);
685 sensor_msgs::PointCloud2ConstIterator<float> iter_x(cloud,
"x");
686 sensor_msgs::PointCloud2ConstIterator<float> iter_y(cloud,
"y");
688 for (; iter_x != iter_x.end(); ++iter_x, ++iter_y) {
699 double t = (origin_x - ox) / a;
704 double t = (origin_y - oy) / b;
710 if (wx > map_end_x) {
711 double t = (map_end_x - ox) / a;
712 wx = map_end_x - .001;
715 if (wy > map_end_y) {
716 double t = (map_end_y - oy) / b;
718 wy = map_end_y - .001;
729 unsigned int cell_raytrace_max_range =
cellDistance(clearing_observation.raytrace_max_range_);
730 unsigned int cell_raytrace_min_range =
cellDistance(clearing_observation.raytrace_min_range_);
731 MarkCell marker(costmap_, FREE_SPACE);
733 raytraceLine(marker, x0, y0, x1, y1, cell_raytrace_max_range, cell_raytrace_min_range);
736 ox, oy, wx, wy, clearing_observation.raytrace_max_range_,
737 clearing_observation.raytrace_min_range_, min_x, min_y, max_x,
770 double ox,
double oy,
double wx,
double wy,
double max_range,
double min_range,
771 double * min_x,
double * min_y,
double * max_x,
double * max_y)
773 double dx = wx - ox, dy = wy - oy;
774 double full_distance = hypot(dx, dy);
775 if (full_distance < min_range) {
778 double scale = std::min(1.0, max_range / full_distance);
779 double ex = ox + dx * scale, ey = oy + dy * scale;
780 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