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;
65 auto node = node_.lock();
77 bool track_unknown_space;
78 double transform_tolerance;
81 std::string topics_string;
84 declareParameter(
"footprint_clearing_enabled", rclcpp::ParameterValue(
true));
88 declareParameter(
"observation_sources", rclcpp::ParameterValue(std::string(
"")));
90 auto node = node_.lock();
92 throw std::runtime_error{
"Failed to lock node"};
95 node->get_parameter(name_ +
"." +
"enabled", enabled_);
96 node->get_parameter(name_ +
"." +
"footprint_clearing_enabled", footprint_clearing_enabled_);
99 node->get_parameter(
"track_unknown_space", track_unknown_space);
100 node->get_parameter(
"transform_tolerance", transform_tolerance);
101 node->get_parameter(name_ +
"." +
"observation_sources", topics_string);
103 int combination_method_param{};
104 node->get_parameter(name_ +
"." +
"combination_method", combination_method_param);
111 std::placeholders::_1));
115 "Subscribed to Topics: %s", topics_string.c_str());
117 rolling_window_ = layered_costmap_->
isRolling();
119 if (track_unknown_space) {
120 default_value_ = NO_INFORMATION;
122 default_value_ = FREE_SPACE;
131 auto sub_opt = rclcpp::SubscriptionOptions();
132 sub_opt.callback_group = callback_group_;
135 std::stringstream ss(topics_string);
138 while (ss >> source) {
140 double observation_keep_time, expected_update_rate, min_obstacle_height, max_obstacle_height;
141 std::string topic, sensor_frame, data_type;
142 bool inf_is_valid, clearing, marking;
145 declareParameter(source +
"." +
"sensor_frame", rclcpp::ParameterValue(std::string(
"")));
146 declareParameter(source +
"." +
"observation_persistence", rclcpp::ParameterValue(0.0));
147 declareParameter(source +
"." +
"expected_update_rate", rclcpp::ParameterValue(0.0));
148 declareParameter(source +
"." +
"data_type", rclcpp::ParameterValue(std::string(
"LaserScan")));
149 declareParameter(source +
"." +
"min_obstacle_height", rclcpp::ParameterValue(0.0));
150 declareParameter(source +
"." +
"max_obstacle_height", rclcpp::ParameterValue(0.0));
151 declareParameter(source +
"." +
"inf_is_valid", rclcpp::ParameterValue(
false));
154 declareParameter(source +
"." +
"obstacle_max_range", rclcpp::ParameterValue(2.5));
155 declareParameter(source +
"." +
"obstacle_min_range", rclcpp::ParameterValue(0.0));
156 declareParameter(source +
"." +
"raytrace_max_range", rclcpp::ParameterValue(3.0));
157 declareParameter(source +
"." +
"raytrace_min_range", rclcpp::ParameterValue(0.0));
159 node->get_parameter(name_ +
"." + source +
"." +
"topic", topic);
160 node->get_parameter(name_ +
"." + source +
"." +
"sensor_frame", sensor_frame);
162 name_ +
"." + source +
"." +
"observation_persistence",
163 observation_keep_time);
165 name_ +
"." + source +
"." +
"expected_update_rate",
166 expected_update_rate);
167 node->get_parameter(name_ +
"." + source +
"." +
"data_type", data_type);
168 node->get_parameter(name_ +
"." + source +
"." +
"min_obstacle_height", min_obstacle_height);
169 node->get_parameter(name_ +
"." + source +
"." +
"max_obstacle_height", max_obstacle_height);
170 node->get_parameter(name_ +
"." + source +
"." +
"inf_is_valid", inf_is_valid);
171 node->get_parameter(name_ +
"." + source +
"." +
"marking", marking);
172 node->get_parameter(name_ +
"." + source +
"." +
"clearing", clearing);
174 if (!(data_type ==
"PointCloud2" || data_type ==
"LaserScan")) {
177 "Only topics that use point cloud2s or laser scans are currently supported");
178 throw std::runtime_error(
179 "Only topics that use point cloud2s or laser scans are currently supported");
183 double obstacle_max_range, obstacle_min_range;
184 node->get_parameter(name_ +
"." + source +
"." +
"obstacle_max_range", obstacle_max_range);
185 node->get_parameter(name_ +
"." + source +
"." +
"obstacle_min_range", obstacle_min_range);
188 double raytrace_max_range, raytrace_min_range;
189 node->get_parameter(name_ +
"." + source +
"." +
"raytrace_min_range", raytrace_min_range);
190 node->get_parameter(name_ +
"." + source +
"." +
"raytrace_max_range", raytrace_max_range);
195 "Creating an observation buffer for source %s, topic %s, frame %s",
196 source.c_str(), topic.c_str(),
197 sensor_frame.c_str());
204 node, topic, observation_keep_time, expected_update_rate,
206 max_obstacle_height, obstacle_max_range, obstacle_min_range, raytrace_max_range,
207 raytrace_min_range, *tf_,
209 sensor_frame, tf2::durationFromSec(transform_tolerance))));
223 "Created an observation buffer for source %s, topic %s, global frame: %s, "
224 "expected update rate: %.2f, observation persistence: %.2f",
225 source.c_str(), topic.c_str(),
226 global_frame_.c_str(), expected_update_rate, observation_keep_time);
228 rmw_qos_profile_t custom_qos_profile = rmw_qos_profile_sensor_data;
229 custom_qos_profile.depth = 50;
232 if (data_type ==
"LaserScan") {
233 auto sub = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
234 rclcpp_lifecycle::LifecycleNode>>(node, topic, custom_qos_profile, sub_opt);
237 auto filter = std::make_shared<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>>(
239 node->get_node_logging_interface(),
240 node->get_node_clock_interface(),
241 tf2::durationFromSec(transform_tolerance));
244 filter->registerCallback(
250 filter->registerCallback(
262 auto sub = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::PointCloud2,
263 rclcpp_lifecycle::LifecycleNode>>(node, topic, custom_qos_profile, sub_opt);
269 "obstacle_layer: inf_is_valid option is not applicable to PointCloud observations.");
272 auto filter = std::make_shared<tf2_ros::MessageFilter<sensor_msgs::msg::PointCloud2>>(
274 node->get_node_logging_interface(),
275 node->get_node_clock_interface(),
276 tf2::durationFromSec(transform_tolerance));
278 filter->registerCallback(
287 if (sensor_frame !=
"") {
288 std::vector<std::string> target_frames;
290 target_frames.push_back(sensor_frame);
296 rcl_interfaces::msg::SetParametersResult
298 std::vector<rclcpp::Parameter> parameters)
300 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
301 rcl_interfaces::msg::SetParametersResult result;
303 for (
auto parameter : parameters) {
304 const auto & param_type = parameter.get_type();
305 const auto & param_name = parameter.get_name();
307 if (param_type == ParameterType::PARAMETER_DOUBLE) {
308 if (param_name == name_ +
"." +
"min_obstacle_height") {
310 }
else if (param_name == name_ +
"." +
"max_obstacle_height") {
313 }
else if (param_type == ParameterType::PARAMETER_BOOL) {
314 if (param_name == name_ +
"." +
"enabled" && enabled_ != parameter.as_bool()) {
315 enabled_ = parameter.as_bool();
319 }
else if (param_name == name_ +
"." +
"footprint_clearing_enabled") {
320 footprint_clearing_enabled_ = parameter.as_bool();
322 }
else if (param_type == ParameterType::PARAMETER_INTEGER) {
323 if (param_name == name_ +
"." +
"combination_method") {
329 result.successful =
true;
335 sensor_msgs::msg::LaserScan::ConstSharedPtr message,
336 const std::shared_ptr<nav2_costmap_2d::ObservationBuffer> & buffer)
339 sensor_msgs::msg::PointCloud2 cloud;
340 cloud.header = message->header;
344 projector_.transformLaserScanToPointCloud(message->header.frame_id, *message, cloud, *tf_);
345 }
catch (tf2::TransformException & ex) {
348 "High fidelity enabled, but TF returned a transform exception to frame %s: %s",
352 }
catch (std::runtime_error & ex) {
355 "transformLaserScanToPointCloud error, it seems the message from laser is malformed."
356 " Ignore this message. what(): %s",
363 buffer->bufferCloud(cloud);
369 sensor_msgs::msg::LaserScan::ConstSharedPtr raw_message,
370 const std::shared_ptr<nav2_costmap_2d::ObservationBuffer> & buffer)
373 float epsilon = 0.0001;
374 sensor_msgs::msg::LaserScan message = *raw_message;
375 for (
size_t i = 0; i < message.ranges.size(); i++) {
376 float range = message.ranges[i];
377 if (!std::isfinite(range) && range > 0) {
378 message.ranges[i] = message.range_max - epsilon;
383 sensor_msgs::msg::PointCloud2 cloud;
384 cloud.header = message.header;
388 projector_.transformLaserScanToPointCloud(message.header.frame_id, message, cloud, *tf_);
389 }
catch (tf2::TransformException & ex) {
392 "High fidelity enabled, but TF returned a transform exception to frame %s: %s",
395 }
catch (std::runtime_error & ex) {
398 "transformLaserScanToPointCloud error, it seems the message from laser is malformed."
399 " Ignore this message. what(): %s",
406 buffer->bufferCloud(cloud);
412 sensor_msgs::msg::PointCloud2::ConstSharedPtr message,
413 const std::shared_ptr<ObservationBuffer> & buffer)
417 buffer->bufferCloud(*message);
423 double robot_x,
double robot_y,
double robot_yaw,
double * min_x,
424 double * min_y,
double * max_x,
double * max_y)
426 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
427 if (rolling_window_) {
433 useExtraBounds(min_x, min_y, max_x, max_y);
436 std::vector<Observation> observations, clearing_observations;
448 for (
unsigned int i = 0; i < clearing_observations.size(); ++i) {
453 for (std::vector<Observation>::const_iterator it = observations.begin();
454 it != observations.end(); ++it)
458 const sensor_msgs::msg::PointCloud2 & cloud = *(obs.cloud_);
460 double sq_obstacle_max_range = obs.obstacle_max_range_ * obs.obstacle_max_range_;
461 double sq_obstacle_min_range = obs.obstacle_min_range_ * obs.obstacle_min_range_;
463 sensor_msgs::PointCloud2ConstIterator<float> iter_x(cloud,
"x");
464 sensor_msgs::PointCloud2ConstIterator<float> iter_y(cloud,
"y");
465 sensor_msgs::PointCloud2ConstIterator<float> iter_z(cloud,
"z");
467 for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) {
468 double px = *iter_x, py = *iter_y, pz = *iter_z;
472 RCLCPP_DEBUG(logger_,
"The point is too low");
478 RCLCPP_DEBUG(logger_,
"The point is too high");
485 obs.origin_.x) * (px - obs.origin_.x) + (py - obs.origin_.y) * (py - obs.origin_.y) +
486 (pz - obs.origin_.z) * (pz - obs.origin_.z);
489 if (sq_dist >= sq_obstacle_max_range) {
490 RCLCPP_DEBUG(logger_,
"The point is too far away");
495 if (sq_dist < sq_obstacle_min_range) {
496 RCLCPP_DEBUG(logger_,
"The point is too close");
503 RCLCPP_DEBUG(logger_,
"Computing map coords failed");
507 unsigned int index =
getIndex(mx, my);
508 costmap_[index] = LETHAL_OBSTACLE;
509 touch(px, py, min_x, min_y, max_x, max_y);
513 updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
518 double robot_x,
double robot_y,
double robot_yaw,
519 double * min_x,
double * min_y,
523 if (!footprint_clearing_enabled_) {
return;}
526 for (
unsigned int i = 0; i < transformed_footprint_.size(); i++) {
527 touch(transformed_footprint_[i].x, transformed_footprint_[i].y, min_x, min_y, max_x, max_y);
537 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
543 if (!current_ && was_reset_) {
548 if (footprint_clearing_enabled_) {
552 switch (combination_method_) {
554 updateWithOverwrite(master_grid, min_i, min_j, max_i, max_j);
557 updateWithMax(master_grid, min_i, min_j, max_i, max_j);
560 updateWithMaxWithoutUnknownOverwrite(master_grid, min_i, min_j, max_i, max_j);
568 ObstacleLayer::addStaticObservation(
570 bool marking,
bool clearing)
573 static_marking_observations_.push_back(obs);
576 static_clearing_observations_.push_back(obs);
581 ObstacleLayer::clearStaticObservations(
bool marking,
bool clearing)
584 static_marking_observations_.clear();
587 static_clearing_observations_.clear();
602 marking_observations.insert(
603 marking_observations.end(),
604 static_marking_observations_.begin(), static_marking_observations_.end());
619 clearing_observations.insert(
620 clearing_observations.end(),
621 static_clearing_observations_.begin(), static_clearing_observations_.end());
627 const Observation & clearing_observation,
double * min_x,
632 double ox = clearing_observation.origin_.x;
633 double oy = clearing_observation.origin_.y;
634 const sensor_msgs::msg::PointCloud2 & cloud = *(clearing_observation.cloud_);
641 "Sensor origin at (%.2f, %.2f) is out of map bounds (%.2f, %.2f) to (%.2f, %.2f). "
642 "The costmap cannot raytrace for it.",
644 origin_x_, origin_y_,
650 double origin_x = origin_x_, origin_y = origin_y_;
651 double map_end_x = origin_x + size_x_ * resolution_;
652 double map_end_y = origin_y + size_y_ * resolution_;
655 touch(ox, oy, min_x, min_y, max_x, max_y);
659 sensor_msgs::PointCloud2ConstIterator<float> iter_x(cloud,
"x");
660 sensor_msgs::PointCloud2ConstIterator<float> iter_y(cloud,
"y");
662 for (; iter_x != iter_x.end(); ++iter_x, ++iter_y) {
673 double t = (origin_x - ox) / a;
678 double t = (origin_y - oy) / b;
684 if (wx > map_end_x) {
685 double t = (map_end_x - ox) / a;
686 wx = map_end_x - .001;
689 if (wy > map_end_y) {
690 double t = (map_end_y - oy) / b;
692 wy = map_end_y - .001;
703 unsigned int cell_raytrace_max_range =
cellDistance(clearing_observation.raytrace_max_range_);
704 unsigned int cell_raytrace_min_range =
cellDistance(clearing_observation.raytrace_min_range_);
705 MarkCell marker(costmap_, FREE_SPACE);
707 raytraceLine(marker, x0, y0, x1, y1, cell_raytrace_max_range, cell_raytrace_min_range);
710 ox, oy, wx, wy, clearing_observation.raytrace_max_range_,
711 clearing_observation.raytrace_min_range_, min_x, min_y, max_x,
744 double ox,
double oy,
double wx,
double wy,
double max_range,
double min_range,
745 double * min_x,
double * min_y,
double * max_x,
double * max_y)
747 double dx = wx - ox, dy = wy - oy;
748 double full_distance = hypot(dx, dy);
749 if (full_distance < min_range) {
752 double scale = std::min(1.0, max_range / full_distance);
753 double ex = ox + dx * scale, ey = oy + dy * scale;
754 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.
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