39 #include "nav2_costmap_2d/voxel_layer.hpp"
47 #include "pluginlib/class_list_macros.hpp"
48 #include "sensor_msgs/point_cloud2_iterator.hpp"
53 using nav2_costmap_2d::NO_INFORMATION;
54 using nav2_costmap_2d::LETHAL_OBSTACLE;
55 using nav2_costmap_2d::FREE_SPACE;
56 using rcl_interfaces::msg::ParameterType;
66 declareParameter(
"footprint_clearing_enabled", rclcpp::ParameterValue(
true));
77 auto node = node_.lock();
79 throw std::runtime_error{
"Failed to lock node"};
82 node->get_parameter(name_ +
"." +
"enabled", enabled_);
83 node->get_parameter(name_ +
"." +
"footprint_clearing_enabled", footprint_clearing_enabled_);
86 node->get_parameter(name_ +
"." +
"z_voxels", size_z_);
87 node->get_parameter(name_ +
"." +
"origin_z", origin_z_);
88 node->get_parameter(name_ +
"." +
"z_resolution", z_resolution_);
89 node->get_parameter(name_ +
"." +
"unknown_threshold", unknown_threshold_);
90 node->get_parameter(name_ +
"." +
"mark_threshold", mark_threshold_);
91 node->get_parameter(name_ +
"." +
"publish_voxel_map", publish_voxel_);
93 int combination_method_param{};
94 node->get_parameter(name_ +
"." +
"combination_method", combination_method_param);
97 auto custom_qos = rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable();
100 voxel_pub_ = node->create_publisher<nav2_msgs::msg::VoxelGrid>(
101 "voxel_grid", custom_qos);
102 voxel_pub_->on_activate();
105 clearing_endpoints_pub_ = node->create_publisher<sensor_msgs::msg::PointCloud2>(
106 "clearing_endpoints", custom_qos);
107 clearing_endpoints_pub_->on_activate();
109 unknown_threshold_ += (VOXEL_BITS - size_z_);
113 dyn_params_handler_ = node->add_on_set_parameters_callback(
116 this, std::placeholders::_1));
121 auto node = node_.lock();
122 if (dyn_params_handler_ && node) {
123 node->remove_on_set_parameters_callback(dyn_params_handler_.get());
125 dyn_params_handler_.reset();
130 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
132 voxel_grid_.
resize(size_x_, size_y_, size_z_);
133 assert(voxel_grid_.sizeX() == size_x_ && voxel_grid_.sizeY() == size_y_);
154 double robot_x,
double robot_y,
double robot_yaw,
double * min_x,
155 double * min_y,
double * max_x,
double * max_y)
157 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
159 if (rolling_window_) {
165 useExtraBounds(min_x, min_y, max_x, max_y);
168 std::vector<Observation> observations, clearing_observations;
180 for (
unsigned int i = 0; i < clearing_observations.size(); ++i) {
185 for (std::vector<Observation>::const_iterator it = observations.begin(); it != observations.end();
190 const sensor_msgs::msg::PointCloud2 & cloud = *(obs.cloud_);
192 double sq_obstacle_max_range = obs.obstacle_max_range_ * obs.obstacle_max_range_;
193 double sq_obstacle_min_range = obs.obstacle_min_range_ * obs.obstacle_min_range_;
195 sensor_msgs::PointCloud2ConstIterator<float> iter_x(cloud,
"x");
196 sensor_msgs::PointCloud2ConstIterator<float> iter_y(cloud,
"y");
197 sensor_msgs::PointCloud2ConstIterator<float> iter_z(cloud,
"z");
199 for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) {
211 double sq_dist = (*iter_x - obs.origin_.x) * (*iter_x - obs.origin_.x) +
212 (*iter_y - obs.origin_.y) * (*iter_y - obs.origin_.y) +
213 (*iter_z - obs.origin_.z) * (*iter_z - obs.origin_.z);
216 if (sq_dist >= sq_obstacle_max_range) {
221 if (sq_dist < sq_obstacle_min_range) {
226 unsigned int mx, my, mz;
227 if (*iter_z < origin_z_) {
228 if (!
worldToMap3D(*iter_x, *iter_y, origin_z_, mx, my, mz)) {
231 }
else if (!
worldToMap3D(*iter_x, *iter_y, *iter_z, mx, my, mz)) {
236 if (voxel_grid_.markVoxelInMap(mx, my, mz, mark_threshold_)) {
237 unsigned int index =
getIndex(mx, my);
239 costmap_[index] = LETHAL_OBSTACLE;
241 static_cast<double>(*iter_x),
static_cast<double>(*iter_y),
242 min_x, min_y, max_x, max_y);
247 if (publish_voxel_) {
248 auto grid_msg = std::make_unique<nav2_msgs::msg::VoxelGrid>();
249 unsigned int size = voxel_grid_.sizeX() * voxel_grid_.sizeY();
250 grid_msg->size_x = voxel_grid_.sizeX();
251 grid_msg->size_y = voxel_grid_.sizeY();
252 grid_msg->size_z = voxel_grid_.sizeZ();
253 grid_msg->data.resize(size);
254 memcpy(&grid_msg->data[0], voxel_grid_.getData(), size *
sizeof(
unsigned int));
256 grid_msg->origin.x = origin_x_;
257 grid_msg->origin.y = origin_y_;
258 grid_msg->origin.z = origin_z_;
260 grid_msg->resolutions.x = resolution_;
261 grid_msg->resolutions.y = resolution_;
262 grid_msg->resolutions.z = z_resolution_;
264 grid_msg->header.stamp = clock_->now();
266 voxel_pub_->publish(std::move(grid_msg));
269 updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
273 const Observation & clearing_observation,
double * min_x,
278 auto clearing_endpoints_ = std::make_unique<sensor_msgs::msg::PointCloud2>();
280 if (clearing_observation.cloud_->height == 0 || clearing_observation.cloud_->width == 0) {
284 double sensor_x, sensor_y, sensor_z;
285 double ox = clearing_observation.origin_.x;
286 double oy = clearing_observation.origin_.y;
287 double oz = clearing_observation.origin_.z;
292 "Sensor origin at (%.2f, %.2f %.2f) is out of map bounds "
293 "(%.2f, %.2f, %.2f) to (%.2f, %.2f, %.2f). "
294 "The costmap cannot raytrace for it.",
296 origin_x_, origin_y_, origin_z_,
303 bool publish_clearing_points;
306 auto node = node_.lock();
308 throw std::runtime_error{
"Failed to lock node"};
310 publish_clearing_points = (node->count_subscribers(
"clearing_endpoints") > 0);
313 clearing_endpoints_->data.clear();
314 clearing_endpoints_->width = clearing_observation.cloud_->width;
315 clearing_endpoints_->height = clearing_observation.cloud_->height;
316 clearing_endpoints_->is_dense =
true;
317 clearing_endpoints_->is_bigendian =
false;
319 sensor_msgs::PointCloud2Modifier modifier(*clearing_endpoints_);
320 modifier.setPointCloud2Fields(
321 3,
"x", 1, sensor_msgs::msg::PointField::FLOAT32,
322 "y", 1, sensor_msgs::msg::PointField::FLOAT32,
323 "z", 1, sensor_msgs::msg::PointField::FLOAT32);
325 sensor_msgs::PointCloud2Iterator<float> clearing_endpoints_iter_x(*clearing_endpoints_,
"x");
326 sensor_msgs::PointCloud2Iterator<float> clearing_endpoints_iter_y(*clearing_endpoints_,
"y");
327 sensor_msgs::PointCloud2Iterator<float> clearing_endpoints_iter_z(*clearing_endpoints_,
"z");
334 sensor_msgs::PointCloud2ConstIterator<float> iter_x(*(clearing_observation.cloud_),
"x");
335 sensor_msgs::PointCloud2ConstIterator<float> iter_y(*(clearing_observation.cloud_),
"y");
336 sensor_msgs::PointCloud2ConstIterator<float> iter_z(*(clearing_observation.cloud_),
"z");
338 for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) {
339 double wpx = *iter_x;
340 double wpy = *iter_y;
341 double wpz = *iter_z;
343 double distance =
dist(ox, oy, oz, wpx, wpy, wpz);
344 double scaling_fact = 1.0;
345 scaling_fact = std::max(std::min(scaling_fact, (distance - 2 * resolution_) / distance), 0.0);
346 wpx = scaling_fact * (wpx - ox) + ox;
347 wpy = scaling_fact * (wpy - oy) + oy;
348 wpz = scaling_fact * (wpz - oz) + oz;
354 bool wp_outside =
false;
357 if (wpz > map_end_z) {
359 t = std::max(0.0, std::min(t, (map_end_z - 0.01 - oz) / c));
361 }
else if (wpz < origin_z_) {
364 t = std::min(t, (origin_z_ - oz) / c);
369 if (wpx < origin_x_) {
370 t = std::min(t, (origin_x_ - ox) / a);
373 if (wpy < origin_y_) {
374 t = std::min(t, (origin_y_ - oy) / b);
379 if (wpx > map_end_x) {
380 t = std::min(t, (map_end_x - ox) / a);
383 if (wpy > map_end_y) {
384 t = std::min(t, (map_end_y - oy) / b);
388 constexpr
double wp_epsilon = 1e-5;
392 }
else if (t < 0.0) {
401 double point_x, point_y, point_z;
403 unsigned int cell_raytrace_max_range =
cellDistance(clearing_observation.raytrace_max_range_);
404 unsigned int cell_raytrace_min_range =
cellDistance(clearing_observation.raytrace_min_range_);
408 voxel_grid_.clearVoxelLineInMap(
409 sensor_x, sensor_y, sensor_z, point_x, point_y, point_z,
411 unknown_threshold_, mark_threshold_, FREE_SPACE, NO_INFORMATION,
412 cell_raytrace_max_range, cell_raytrace_min_range);
415 ox, oy, wpx, wpy, clearing_observation.raytrace_max_range_,
416 clearing_observation.raytrace_min_range_, min_x, min_y,
420 if (publish_clearing_points) {
421 *clearing_endpoints_iter_x = wpx;
422 *clearing_endpoints_iter_y = wpy;
423 *clearing_endpoints_iter_z = wpz;
425 ++clearing_endpoints_iter_x;
426 ++clearing_endpoints_iter_y;
427 ++clearing_endpoints_iter_z;
432 if (publish_clearing_points) {
434 clearing_endpoints_->header.stamp = clearing_observation.cloud_->header.stamp;
436 clearing_endpoints_pub_->publish(std::move(clearing_endpoints_));
443 int cell_ox, cell_oy;
444 cell_ox =
static_cast<int>((new_origin_x - origin_x_) / resolution_);
445 cell_oy =
static_cast<int>((new_origin_y - origin_y_) / resolution_);
449 double new_grid_ox, new_grid_oy;
450 new_grid_ox = origin_x_ + cell_ox * resolution_;
451 new_grid_oy = origin_y_ + cell_oy * resolution_;
454 int size_x = size_x_;
455 int size_y = size_y_;
458 int lower_left_x, lower_left_y, upper_right_x, upper_right_y;
459 lower_left_x = std::min(std::max(cell_ox, 0), size_x);
460 lower_left_y = std::min(std::max(cell_oy, 0), size_y);
461 upper_right_x = std::min(std::max(cell_ox + size_x, 0), size_x);
462 upper_right_y = std::min(std::max(cell_oy + size_y, 0), size_y);
464 unsigned int cell_size_x = upper_right_x - lower_left_x;
465 unsigned int cell_size_y = upper_right_y - lower_left_y;
468 unsigned char * local_map =
new unsigned char[cell_size_x * cell_size_y];
469 unsigned int * local_voxel_map =
new unsigned int[cell_size_x * cell_size_y];
470 unsigned int * voxel_map = voxel_grid_.getData();
474 costmap_, lower_left_x, lower_left_y, size_x_, local_map, 0, 0, cell_size_x,
478 voxel_map, lower_left_x, lower_left_y, size_x_, local_voxel_map, 0, 0, cell_size_x,
486 origin_x_ = new_grid_ox;
487 origin_y_ = new_grid_oy;
490 int start_x = lower_left_x - cell_ox;
491 int start_y = lower_left_y - cell_oy;
495 local_map, 0, 0, cell_size_x, costmap_, start_x, start_y, size_x_, cell_size_x,
498 local_voxel_map, 0, 0, cell_size_x, voxel_map, start_x, start_y, size_x_,
504 delete[] local_voxel_map;
511 rcl_interfaces::msg::SetParametersResult
513 std::vector<rclcpp::Parameter> parameters)
515 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
516 rcl_interfaces::msg::SetParametersResult result;
517 bool resize_map_needed =
false;
519 for (
auto parameter : parameters) {
520 const auto & param_type = parameter.get_type();
521 const auto & param_name = parameter.get_name();
523 if (param_type == ParameterType::PARAMETER_DOUBLE) {
524 if (param_name == name_ +
"." +
"min_obstacle_height") {
526 }
else if (param_name == name_ +
"." +
"max_obstacle_height") {
528 }
else if (param_name == name_ +
"." +
"origin_z") {
529 origin_z_ = parameter.as_double();
530 resize_map_needed =
true;
531 }
else if (param_name == name_ +
"." +
"z_resolution") {
532 z_resolution_ = parameter.as_double();
533 resize_map_needed =
true;
535 }
else if (param_type == ParameterType::PARAMETER_BOOL) {
536 if (param_name == name_ +
"." +
"enabled") {
537 enabled_ = parameter.as_bool();
539 }
else if (param_name == name_ +
"." +
"footprint_clearing_enabled") {
540 footprint_clearing_enabled_ = parameter.as_bool();
541 }
else if (param_name == name_ +
"." +
"publish_voxel_map") {
543 logger_,
"publish voxel map is not a dynamic parameter "
544 "cannot be changed while running. Rejecting parameter update.");
548 }
else if (param_type == ParameterType::PARAMETER_INTEGER) {
549 if (param_name == name_ +
"." +
"z_voxels") {
550 size_z_ = parameter.as_int();
551 resize_map_needed =
true;
552 }
else if (param_name == name_ +
"." +
"unknown_threshold") {
553 unknown_threshold_ = parameter.as_int() + (VOXEL_BITS - size_z_);
554 }
else if (param_name == name_ +
"." +
"mark_threshold") {
555 mark_threshold_ = parameter.as_int();
556 }
else if (param_name == name_ +
"." +
"combination_method") {
562 if (resize_map_needed) {
566 result.successful =
true;
unsigned int getIndex(unsigned int mx, unsigned int my) const
Given two map coordinates... compute the associated index.
void copyMapRegion(data_type *source_map, unsigned int sm_lower_left_x, unsigned int sm_lower_left_y, unsigned int sm_size_x, data_type *dest_map, unsigned int dm_lower_left_x, unsigned int dm_lower_left_y, unsigned int dm_size_x, unsigned int region_size_x, unsigned int region_size_y)
Copy a region of a source map into a destination map.
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.
Stores an observation in terms of a point cloud and the origin of the source.
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.
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 onInitialize()
Initialization process of layer on startup.
double min_obstacle_height_
Max Obstacle Height.
double max_obstacle_height_
Max Obstacle Height.
virtual void reset()
Reset this costmap.
Takes laser and pointcloud data to populate a 3D voxel representation of the environment.
virtual void onInitialize()
Initialization process of layer on startup.
virtual ~VoxelLayer()
Voxel Layer destructor.
double getSizeInMetersZ() const
Get the height of the voxel sizes in meters.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
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 updateOrigin(double new_origin_x, double new_origin_y)
Update the layer's origin to a new pose, often when in a rolling costmap.
bool worldToMap3DFloat(double wx, double wy, double wz, double &mx, double &my, double &mz)
Covert world coordinates into map coordinates.
bool worldToMap3D(double wx, double wy, double wz, unsigned int &mx, unsigned int &my, unsigned int &mz)
Covert world coordinates into map coordinates.
virtual void resetMaps()
Reset internal maps.
virtual void matchSize()
Match the size of the master costmap.
virtual void reset()
Reset this costmap.
double dist(double x0, double y0, double z0, double x1, double y1, double z1)
Find L2 norm distance in 3D.
virtual void raytraceFreespace(const nav2_costmap_2d::Observation &clearing_observation, double *min_x, double *min_y, double *max_x, double *max_y)
Use raycasting between 2 points to clear freespace.
void resize(unsigned int size_x, unsigned int size_y, unsigned int size_z)
Resizes a voxel grid to the desired size.