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);
98 voxel_pub_ = node->create_publisher<nav2_msgs::msg::VoxelGrid>(
100 voxel_pub_->on_activate();
103 clearing_endpoints_pub_ = node->create_publisher<sensor_msgs::msg::PointCloud2>(
105 clearing_endpoints_pub_->on_activate();
107 unknown_threshold_ += (VOXEL_BITS - size_z_);
111 dyn_params_handler_ = node->add_on_set_parameters_callback(
114 this, std::placeholders::_1));
119 auto node = node_.lock();
120 if (dyn_params_handler_ && node) {
121 node->remove_on_set_parameters_callback(dyn_params_handler_.get());
123 dyn_params_handler_.reset();
128 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
130 voxel_grid_.
resize(size_x_, size_y_, size_z_);
131 assert(voxel_grid_.sizeX() == size_x_ && voxel_grid_.sizeY() == size_y_);
152 double robot_x,
double robot_y,
double robot_yaw,
double * min_x,
153 double * min_y,
double * max_x,
double * max_y)
155 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
157 if (rolling_window_) {
163 useExtraBounds(min_x, min_y, max_x, max_y);
166 std::vector<Observation> observations, clearing_observations;
178 for (
unsigned int i = 0; i < clearing_observations.size(); ++i) {
183 for (std::vector<Observation>::const_iterator it = observations.begin(); it != observations.end();
188 const sensor_msgs::msg::PointCloud2 & cloud = *(obs.cloud_);
190 double sq_obstacle_max_range = obs.obstacle_max_range_ * obs.obstacle_max_range_;
191 double sq_obstacle_min_range = obs.obstacle_min_range_ * obs.obstacle_min_range_;
193 sensor_msgs::PointCloud2ConstIterator<float> iter_x(cloud,
"x");
194 sensor_msgs::PointCloud2ConstIterator<float> iter_y(cloud,
"y");
195 sensor_msgs::PointCloud2ConstIterator<float> iter_z(cloud,
"z");
197 for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) {
209 double sq_dist = (*iter_x - obs.origin_.x) * (*iter_x - obs.origin_.x) +
210 (*iter_y - obs.origin_.y) * (*iter_y - obs.origin_.y) +
211 (*iter_z - obs.origin_.z) * (*iter_z - obs.origin_.z);
214 if (sq_dist >= sq_obstacle_max_range) {
219 if (sq_dist < sq_obstacle_min_range) {
224 unsigned int mx, my, mz;
225 if (*iter_z < origin_z_) {
226 if (!
worldToMap3D(*iter_x, *iter_y, origin_z_, mx, my, mz)) {
229 }
else if (!
worldToMap3D(*iter_x, *iter_y, *iter_z, mx, my, mz)) {
234 if (voxel_grid_.markVoxelInMap(mx, my, mz, mark_threshold_)) {
235 unsigned int index =
getIndex(mx, my);
237 costmap_[index] = LETHAL_OBSTACLE;
239 static_cast<double>(*iter_x),
static_cast<double>(*iter_y),
240 min_x, min_y, max_x, max_y);
245 if (publish_voxel_) {
246 auto grid_msg = std::make_unique<nav2_msgs::msg::VoxelGrid>();
247 unsigned int size = voxel_grid_.sizeX() * voxel_grid_.sizeY();
248 grid_msg->size_x = voxel_grid_.sizeX();
249 grid_msg->size_y = voxel_grid_.sizeY();
250 grid_msg->size_z = voxel_grid_.sizeZ();
251 grid_msg->data.resize(size);
252 memcpy(&grid_msg->data[0], voxel_grid_.getData(), size *
sizeof(
unsigned int));
254 grid_msg->origin.x = origin_x_;
255 grid_msg->origin.y = origin_y_;
256 grid_msg->origin.z = origin_z_;
258 grid_msg->resolutions.x = resolution_;
259 grid_msg->resolutions.y = resolution_;
260 grid_msg->resolutions.z = z_resolution_;
262 grid_msg->header.stamp = clock_->now();
264 voxel_pub_->publish(std::move(grid_msg));
267 updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
271 const Observation & clearing_observation,
double * min_x,
276 auto clearing_endpoints_ = std::make_unique<sensor_msgs::msg::PointCloud2>();
278 if (clearing_observation.cloud_->height == 0 || clearing_observation.cloud_->width == 0) {
282 double sensor_x, sensor_y, sensor_z;
283 double ox = clearing_observation.origin_.x;
284 double oy = clearing_observation.origin_.y;
285 double oz = clearing_observation.origin_.z;
290 "Sensor origin at (%.2f, %.2f %.2f) is out of map bounds "
291 "(%.2f, %.2f, %.2f) to (%.2f, %.2f, %.2f). "
292 "The costmap cannot raytrace for it.",
294 origin_x_, origin_y_, origin_z_,
301 bool publish_clearing_points;
304 auto node = node_.lock();
306 throw std::runtime_error{
"Failed to lock node"};
308 publish_clearing_points = (node->count_subscribers(
"clearing_endpoints") > 0);
311 clearing_endpoints_->data.clear();
312 clearing_endpoints_->width = clearing_observation.cloud_->width;
313 clearing_endpoints_->height = clearing_observation.cloud_->height;
314 clearing_endpoints_->is_dense =
true;
315 clearing_endpoints_->is_bigendian =
false;
317 sensor_msgs::PointCloud2Modifier modifier(*clearing_endpoints_);
318 modifier.setPointCloud2Fields(
319 3,
"x", 1, sensor_msgs::msg::PointField::FLOAT32,
320 "y", 1, sensor_msgs::msg::PointField::FLOAT32,
321 "z", 1, sensor_msgs::msg::PointField::FLOAT32);
323 sensor_msgs::PointCloud2Iterator<float> clearing_endpoints_iter_x(*clearing_endpoints_,
"x");
324 sensor_msgs::PointCloud2Iterator<float> clearing_endpoints_iter_y(*clearing_endpoints_,
"y");
325 sensor_msgs::PointCloud2Iterator<float> clearing_endpoints_iter_z(*clearing_endpoints_,
"z");
332 sensor_msgs::PointCloud2ConstIterator<float> iter_x(*(clearing_observation.cloud_),
"x");
333 sensor_msgs::PointCloud2ConstIterator<float> iter_y(*(clearing_observation.cloud_),
"y");
334 sensor_msgs::PointCloud2ConstIterator<float> iter_z(*(clearing_observation.cloud_),
"z");
336 for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) {
337 double wpx = *iter_x;
338 double wpy = *iter_y;
339 double wpz = *iter_z;
341 double distance =
dist(ox, oy, oz, wpx, wpy, wpz);
342 double scaling_fact = 1.0;
343 scaling_fact = std::max(std::min(scaling_fact, (distance - 2 * resolution_) / distance), 0.0);
344 wpx = scaling_fact * (wpx - ox) + ox;
345 wpy = scaling_fact * (wpy - oy) + oy;
346 wpz = scaling_fact * (wpz - oz) + oz;
352 bool wp_outside =
false;
355 if (wpz > map_end_z) {
357 t = std::max(0.0, std::min(t, (map_end_z - 0.01 - oz) / c));
359 }
else if (wpz < origin_z_) {
362 t = std::min(t, (origin_z_ - oz) / c);
367 if (wpx < origin_x_) {
368 t = std::min(t, (origin_x_ - ox) / a);
371 if (wpy < origin_y_) {
372 t = std::min(t, (origin_y_ - oy) / b);
377 if (wpx > map_end_x) {
378 t = std::min(t, (map_end_x - ox) / a);
381 if (wpy > map_end_y) {
382 t = std::min(t, (map_end_y - oy) / b);
386 constexpr
double wp_epsilon = 1e-5;
390 }
else if (t < 0.0) {
399 double point_x, point_y, point_z;
401 unsigned int cell_raytrace_max_range =
cellDistance(clearing_observation.raytrace_max_range_);
402 unsigned int cell_raytrace_min_range =
cellDistance(clearing_observation.raytrace_min_range_);
406 voxel_grid_.clearVoxelLineInMap(
407 sensor_x, sensor_y, sensor_z, point_x, point_y, point_z,
409 unknown_threshold_, mark_threshold_, FREE_SPACE, NO_INFORMATION,
410 cell_raytrace_max_range, cell_raytrace_min_range);
413 ox, oy, wpx, wpy, clearing_observation.raytrace_max_range_,
414 clearing_observation.raytrace_min_range_, min_x, min_y,
418 if (publish_clearing_points) {
419 *clearing_endpoints_iter_x = wpx;
420 *clearing_endpoints_iter_y = wpy;
421 *clearing_endpoints_iter_z = wpz;
423 ++clearing_endpoints_iter_x;
424 ++clearing_endpoints_iter_y;
425 ++clearing_endpoints_iter_z;
430 if (publish_clearing_points) {
432 clearing_endpoints_->header.stamp = clearing_observation.cloud_->header.stamp;
434 clearing_endpoints_pub_->publish(std::move(clearing_endpoints_));
441 int cell_ox, cell_oy;
442 cell_ox =
static_cast<int>((new_origin_x - origin_x_) / resolution_);
443 cell_oy =
static_cast<int>((new_origin_y - origin_y_) / resolution_);
447 double new_grid_ox, new_grid_oy;
448 new_grid_ox = origin_x_ + cell_ox * resolution_;
449 new_grid_oy = origin_y_ + cell_oy * resolution_;
452 int size_x = size_x_;
453 int size_y = size_y_;
456 int lower_left_x, lower_left_y, upper_right_x, upper_right_y;
457 lower_left_x = std::min(std::max(cell_ox, 0), size_x);
458 lower_left_y = std::min(std::max(cell_oy, 0), size_y);
459 upper_right_x = std::min(std::max(cell_ox + size_x, 0), size_x);
460 upper_right_y = std::min(std::max(cell_oy + size_y, 0), size_y);
462 unsigned int cell_size_x = upper_right_x - lower_left_x;
463 unsigned int cell_size_y = upper_right_y - lower_left_y;
466 unsigned char * local_map =
new unsigned char[cell_size_x * cell_size_y];
467 unsigned int * local_voxel_map =
new unsigned int[cell_size_x * cell_size_y];
468 unsigned int * voxel_map = voxel_grid_.getData();
472 costmap_, lower_left_x, lower_left_y, size_x_, local_map, 0, 0, cell_size_x,
476 voxel_map, lower_left_x, lower_left_y, size_x_, local_voxel_map, 0, 0, cell_size_x,
484 origin_x_ = new_grid_ox;
485 origin_y_ = new_grid_oy;
488 int start_x = lower_left_x - cell_ox;
489 int start_y = lower_left_y - cell_oy;
493 local_map, 0, 0, cell_size_x, costmap_, start_x, start_y, size_x_, cell_size_x,
496 local_voxel_map, 0, 0, cell_size_x, voxel_map, start_x, start_y, size_x_,
502 delete[] local_voxel_map;
509 rcl_interfaces::msg::SetParametersResult
511 std::vector<rclcpp::Parameter> parameters)
513 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
514 rcl_interfaces::msg::SetParametersResult result;
515 bool resize_map_needed =
false;
517 for (
auto parameter : parameters) {
518 const auto & param_type = parameter.get_type();
519 const auto & param_name = parameter.get_name();
520 if (param_name.find(name_ +
".") != 0) {
524 if (param_type == ParameterType::PARAMETER_DOUBLE) {
525 if (param_name == name_ +
"." +
"min_obstacle_height") {
527 }
else if (param_name == name_ +
"." +
"max_obstacle_height") {
529 }
else if (param_name == name_ +
"." +
"origin_z") {
530 origin_z_ = parameter.as_double();
531 resize_map_needed =
true;
532 }
else if (param_name == name_ +
"." +
"z_resolution") {
533 z_resolution_ = parameter.as_double();
534 resize_map_needed =
true;
536 }
else if (param_type == ParameterType::PARAMETER_BOOL) {
537 if (param_name == name_ +
"." +
"enabled") {
538 enabled_ = parameter.as_bool();
540 }
else if (param_name == name_ +
"." +
"footprint_clearing_enabled") {
541 footprint_clearing_enabled_ = parameter.as_bool();
542 }
else if (param_name == name_ +
"." +
"publish_voxel_map") {
544 logger_,
"publish voxel map is not a dynamic parameter "
545 "cannot be changed while running. Rejecting parameter update.");
549 }
else if (param_type == ParameterType::PARAMETER_INTEGER) {
550 if (param_name == name_ +
"." +
"z_voxels") {
551 size_z_ = parameter.as_int();
552 resize_map_needed =
true;
553 }
else if (param_name == name_ +
"." +
"unknown_threshold") {
554 unknown_threshold_ = parameter.as_int() + (VOXEL_BITS - size_z_);
555 }
else if (param_name == name_ +
"." +
"mark_threshold") {
556 mark_threshold_ = parameter.as_int();
557 }
else if (param_name == name_ +
"." +
"combination_method") {
563 if (resize_map_needed) {
567 result.successful =
true;
A QoS profile for latched, reliable topics with a history of 1 messages.
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)
Convert world coordinates into map coordinates.
bool worldToMap3D(double wx, double wy, double wz, unsigned int &mx, unsigned int &my, unsigned int &mz)
Convert 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.