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"
52 using nav2_costmap_2d::NO_INFORMATION;
53 using nav2_costmap_2d::LETHAL_OBSTACLE;
54 using nav2_costmap_2d::FREE_SPACE;
58 using rcl_interfaces::msg::ParameterType;
73 bool track_unknown_space;
74 double transform_tolerance;
77 std::string topics_string;
80 declareParameter(
"footprint_clearing_enabled", rclcpp::ParameterValue(
true));
84 declareParameter(
"observation_sources", rclcpp::ParameterValue(std::string(
"")));
86 auto node = node_.lock();
88 throw std::runtime_error{
"Failed to lock node"};
91 node->get_parameter(name_ +
"." +
"enabled", enabled_);
92 node->get_parameter(name_ +
"." +
"footprint_clearing_enabled", footprint_clearing_enabled_);
95 node->get_parameter(name_ +
"." +
"combination_method", combination_method_);
96 node->get_parameter(
"track_unknown_space", track_unknown_space);
97 node->get_parameter(
"transform_tolerance", transform_tolerance);
98 node->get_parameter(name_ +
"." +
"observation_sources", topics_string);
104 std::placeholders::_1));
108 "Subscribed to Topics: %s", topics_string.c_str());
110 rolling_window_ = layered_costmap_->
isRolling();
112 if (track_unknown_space) {
113 default_value_ = NO_INFORMATION;
115 default_value_ = FREE_SPACE;
124 auto sub_opt = rclcpp::SubscriptionOptions();
125 sub_opt.callback_group = callback_group_;
128 std::stringstream ss(topics_string);
131 while (ss >> source) {
133 double observation_keep_time, expected_update_rate, min_obstacle_height, max_obstacle_height;
134 std::string topic, sensor_frame, data_type;
135 bool inf_is_valid, clearing, marking;
138 declareParameter(source +
"." +
"sensor_frame", rclcpp::ParameterValue(std::string(
"")));
139 declareParameter(source +
"." +
"observation_persistence", rclcpp::ParameterValue(0.0));
140 declareParameter(source +
"." +
"expected_update_rate", rclcpp::ParameterValue(0.0));
141 declareParameter(source +
"." +
"data_type", rclcpp::ParameterValue(std::string(
"LaserScan")));
142 declareParameter(source +
"." +
"min_obstacle_height", rclcpp::ParameterValue(0.0));
143 declareParameter(source +
"." +
"max_obstacle_height", rclcpp::ParameterValue(0.0));
144 declareParameter(source +
"." +
"inf_is_valid", rclcpp::ParameterValue(
false));
147 declareParameter(source +
"." +
"obstacle_max_range", rclcpp::ParameterValue(2.5));
148 declareParameter(source +
"." +
"obstacle_min_range", rclcpp::ParameterValue(0.0));
149 declareParameter(source +
"." +
"raytrace_max_range", rclcpp::ParameterValue(3.0));
150 declareParameter(source +
"." +
"raytrace_min_range", rclcpp::ParameterValue(0.0));
152 node->get_parameter(name_ +
"." + source +
"." +
"topic", topic);
153 node->get_parameter(name_ +
"." + source +
"." +
"sensor_frame", sensor_frame);
155 name_ +
"." + source +
"." +
"observation_persistence",
156 observation_keep_time);
158 name_ +
"." + source +
"." +
"expected_update_rate",
159 expected_update_rate);
160 node->get_parameter(name_ +
"." + source +
"." +
"data_type", data_type);
161 node->get_parameter(name_ +
"." + source +
"." +
"min_obstacle_height", min_obstacle_height);
162 node->get_parameter(name_ +
"." + source +
"." +
"max_obstacle_height", max_obstacle_height);
163 node->get_parameter(name_ +
"." + source +
"." +
"inf_is_valid", inf_is_valid);
164 node->get_parameter(name_ +
"." + source +
"." +
"marking", marking);
165 node->get_parameter(name_ +
"." + source +
"." +
"clearing", clearing);
167 if (!(data_type ==
"PointCloud2" || data_type ==
"LaserScan")) {
170 "Only topics that use point cloud2s or laser scans are currently supported");
171 throw std::runtime_error(
172 "Only topics that use point cloud2s or laser scans are currently supported");
176 double obstacle_max_range, obstacle_min_range;
177 node->get_parameter(name_ +
"." + source +
"." +
"obstacle_max_range", obstacle_max_range);
178 node->get_parameter(name_ +
"." + source +
"." +
"obstacle_min_range", obstacle_min_range);
181 double raytrace_max_range, raytrace_min_range;
182 node->get_parameter(name_ +
"." + source +
"." +
"raytrace_min_range", raytrace_min_range);
183 node->get_parameter(name_ +
"." + source +
"." +
"raytrace_max_range", raytrace_max_range);
188 "Creating an observation buffer for source %s, topic %s, frame %s",
189 source.c_str(), topic.c_str(),
190 sensor_frame.c_str());
197 node, topic, observation_keep_time, expected_update_rate,
199 max_obstacle_height, obstacle_max_range, obstacle_min_range, raytrace_max_range,
200 raytrace_min_range, *tf_,
202 sensor_frame, tf2::durationFromSec(transform_tolerance))));
216 "Created an observation buffer for source %s, topic %s, global frame: %s, "
217 "expected update rate: %.2f, observation persistence: %.2f",
218 source.c_str(), topic.c_str(),
219 global_frame_.c_str(), expected_update_rate, observation_keep_time);
221 rmw_qos_profile_t custom_qos_profile = rmw_qos_profile_sensor_data;
222 custom_qos_profile.depth = 50;
225 if (data_type ==
"LaserScan") {
226 auto sub = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
227 rclcpp_lifecycle::LifecycleNode>>(node, topic, custom_qos_profile, sub_opt);
230 auto filter = std::make_shared<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>>(
232 node->get_node_logging_interface(),
233 node->get_node_clock_interface(),
234 tf2::durationFromSec(transform_tolerance));
237 filter->registerCallback(
243 filter->registerCallback(
255 auto sub = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::PointCloud2,
256 rclcpp_lifecycle::LifecycleNode>>(node, topic, custom_qos_profile, sub_opt);
262 "obstacle_layer: inf_is_valid option is not applicable to PointCloud observations.");
265 auto filter = std::make_shared<tf2_ros::MessageFilter<sensor_msgs::msg::PointCloud2>>(
267 node->get_node_logging_interface(),
268 node->get_node_clock_interface(),
269 tf2::durationFromSec(transform_tolerance));
271 filter->registerCallback(
280 if (sensor_frame !=
"") {
281 std::vector<std::string> target_frames;
283 target_frames.push_back(sensor_frame);
289 rcl_interfaces::msg::SetParametersResult
291 std::vector<rclcpp::Parameter> parameters)
293 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
294 rcl_interfaces::msg::SetParametersResult result;
296 for (
auto parameter : parameters) {
297 const auto & param_type = parameter.get_type();
298 const auto & param_name = parameter.get_name();
300 if (param_type == ParameterType::PARAMETER_DOUBLE) {
301 if (param_name == name_ +
"." +
"min_obstacle_height") {
303 }
else if (param_name == name_ +
"." +
"max_obstacle_height") {
306 }
else if (param_type == ParameterType::PARAMETER_BOOL) {
307 if (param_name == name_ +
"." +
"enabled" && enabled_ != parameter.as_bool()) {
308 enabled_ = parameter.as_bool();
312 }
else if (param_name == name_ +
"." +
"footprint_clearing_enabled") {
313 footprint_clearing_enabled_ = parameter.as_bool();
315 }
else if (param_type == ParameterType::PARAMETER_INTEGER) {
316 if (param_name == name_ +
"." +
"combination_method") {
317 combination_method_ = parameter.as_int();
322 result.successful =
true;
328 sensor_msgs::msg::LaserScan::ConstSharedPtr message,
329 const std::shared_ptr<nav2_costmap_2d::ObservationBuffer> & buffer)
332 sensor_msgs::msg::PointCloud2 cloud;
333 cloud.header = message->header;
337 projector_.transformLaserScanToPointCloud(message->header.frame_id, *message, cloud, *tf_);
338 }
catch (tf2::TransformException & ex) {
341 "High fidelity enabled, but TF returned a transform exception to frame %s: %s",
345 }
catch (std::runtime_error & ex) {
348 "transformLaserScanToPointCloud error, it seems the message from laser is malformed."
349 " Ignore this message. what(): %s",
356 buffer->bufferCloud(cloud);
362 sensor_msgs::msg::LaserScan::ConstSharedPtr raw_message,
363 const std::shared_ptr<nav2_costmap_2d::ObservationBuffer> & buffer)
366 float epsilon = 0.0001;
367 sensor_msgs::msg::LaserScan message = *raw_message;
368 for (
size_t i = 0; i < message.ranges.size(); i++) {
369 float range = message.ranges[i];
370 if (!std::isfinite(range) && range > 0) {
371 message.ranges[i] = message.range_max - epsilon;
376 sensor_msgs::msg::PointCloud2 cloud;
377 cloud.header = message.header;
381 projector_.transformLaserScanToPointCloud(message.header.frame_id, message, cloud, *tf_);
382 }
catch (tf2::TransformException & ex) {
385 "High fidelity enabled, but TF returned a transform exception to frame %s: %s",
388 }
catch (std::runtime_error & ex) {
391 "transformLaserScanToPointCloud error, it seems the message from laser is malformed."
392 " Ignore this message. what(): %s",
399 buffer->bufferCloud(cloud);
405 sensor_msgs::msg::PointCloud2::ConstSharedPtr message,
406 const std::shared_ptr<ObservationBuffer> & buffer)
410 buffer->bufferCloud(*message);
416 double robot_x,
double robot_y,
double robot_yaw,
double * min_x,
417 double * min_y,
double * max_x,
double * max_y)
419 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
420 if (rolling_window_) {
426 useExtraBounds(min_x, min_y, max_x, max_y);
429 std::vector<Observation> observations, clearing_observations;
441 for (
unsigned int i = 0; i < clearing_observations.size(); ++i) {
446 for (std::vector<Observation>::const_iterator it = observations.begin();
447 it != observations.end(); ++it)
451 const sensor_msgs::msg::PointCloud2 & cloud = *(obs.cloud_);
453 double sq_obstacle_max_range = obs.obstacle_max_range_ * obs.obstacle_max_range_;
454 double sq_obstacle_min_range = obs.obstacle_min_range_ * obs.obstacle_min_range_;
456 sensor_msgs::PointCloud2ConstIterator<float> iter_x(cloud,
"x");
457 sensor_msgs::PointCloud2ConstIterator<float> iter_y(cloud,
"y");
458 sensor_msgs::PointCloud2ConstIterator<float> iter_z(cloud,
"z");
460 for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) {
461 double px = *iter_x, py = *iter_y, pz = *iter_z;
465 RCLCPP_DEBUG(logger_,
"The point is too low");
471 RCLCPP_DEBUG(logger_,
"The point is too high");
478 obs.origin_.x) * (px - obs.origin_.x) + (py - obs.origin_.y) * (py - obs.origin_.y) +
479 (pz - obs.origin_.z) * (pz - obs.origin_.z);
482 if (sq_dist >= sq_obstacle_max_range) {
483 RCLCPP_DEBUG(logger_,
"The point is too far away");
488 if (sq_dist < sq_obstacle_min_range) {
489 RCLCPP_DEBUG(logger_,
"The point is too close");
496 RCLCPP_DEBUG(logger_,
"Computing map coords failed");
500 unsigned int index =
getIndex(mx, my);
501 costmap_[index] = LETHAL_OBSTACLE;
502 touch(px, py, min_x, min_y, max_x, max_y);
506 updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
511 double robot_x,
double robot_y,
double robot_yaw,
512 double * min_x,
double * min_y,
516 if (!footprint_clearing_enabled_) {
return;}
519 for (
unsigned int i = 0; i < transformed_footprint_.size(); i++) {
520 touch(transformed_footprint_[i].x, transformed_footprint_[i].y, min_x, min_y, max_x, max_y);
530 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
536 if (!current_ && was_reset_) {
541 if (footprint_clearing_enabled_) {
545 switch (combination_method_) {
547 updateWithOverwrite(master_grid, min_i, min_j, max_i, max_j);
550 updateWithMax(master_grid, min_i, min_j, max_i, max_j);
558 ObstacleLayer::addStaticObservation(
560 bool marking,
bool clearing)
563 static_marking_observations_.push_back(obs);
566 static_clearing_observations_.push_back(obs);
571 ObstacleLayer::clearStaticObservations(
bool marking,
bool clearing)
574 static_marking_observations_.clear();
577 static_clearing_observations_.clear();
592 marking_observations.insert(
593 marking_observations.end(),
594 static_marking_observations_.begin(), static_marking_observations_.end());
609 clearing_observations.insert(
610 clearing_observations.end(),
611 static_clearing_observations_.begin(), static_clearing_observations_.end());
617 const Observation & clearing_observation,
double * min_x,
622 double ox = clearing_observation.origin_.x;
623 double oy = clearing_observation.origin_.y;
624 const sensor_msgs::msg::PointCloud2 & cloud = *(clearing_observation.cloud_);
631 "Sensor origin at (%.2f, %.2f) is out of map bounds (%.2f, %.2f) to (%.2f, %.2f). "
632 "The costmap cannot raytrace for it.",
634 origin_x_, origin_y_,
640 double origin_x = origin_x_, origin_y = origin_y_;
641 double map_end_x = origin_x + size_x_ * resolution_;
642 double map_end_y = origin_y + size_y_ * resolution_;
645 touch(ox, oy, min_x, min_y, max_x, max_y);
649 sensor_msgs::PointCloud2ConstIterator<float> iter_x(cloud,
"x");
650 sensor_msgs::PointCloud2ConstIterator<float> iter_y(cloud,
"y");
652 for (; iter_x != iter_x.end(); ++iter_x, ++iter_y) {
663 double t = (origin_x - ox) / a;
668 double t = (origin_y - oy) / b;
674 if (wx > map_end_x) {
675 double t = (map_end_x - ox) / a;
676 wx = map_end_x - .001;
679 if (wy > map_end_y) {
680 double t = (map_end_y - oy) / b;
682 wy = map_end_y - .001;
693 unsigned int cell_raytrace_max_range =
cellDistance(clearing_observation.raytrace_max_range_);
694 unsigned int cell_raytrace_min_range =
cellDistance(clearing_observation.raytrace_min_range_);
695 MarkCell marker(costmap_, FREE_SPACE);
697 raytraceLine(marker, x0, y0, x1, y1, cell_raytrace_max_range, cell_raytrace_min_range);
700 ox, oy, wx, wy, clearing_observation.raytrace_max_range_,
701 clearing_observation.raytrace_min_range_, min_x, min_y, max_x,
734 double ox,
double oy,
double wx,
double wy,
double max_range,
double min_range,
735 double * min_x,
double * min_y,
double * max_x,
double * max_y)
737 double dx = wx - ox, dy = wy - oy;
738 double full_distance = hypot(dx, dy);
739 if (full_distance < min_range) {
742 double scale = std::min(1.0, max_range / full_distance);
743 double ex = ox + dx * scale, ey = oy + dy * scale;
744 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.
Abstract class for layered costmap plugin implementations.
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)