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));
76 auto node = node_.lock();
78 throw std::runtime_error{
"Failed to lock node"};
81 node->get_parameter(name_ +
"." +
"enabled", enabled_);
82 node->get_parameter(name_ +
"." +
"footprint_clearing_enabled", footprint_clearing_enabled_);
84 node->get_parameter(name_ +
"." +
"z_voxels", size_z_);
85 node->get_parameter(name_ +
"." +
"origin_z", origin_z_);
86 node->get_parameter(name_ +
"." +
"z_resolution", z_resolution_);
87 node->get_parameter(name_ +
"." +
"unknown_threshold", unknown_threshold_);
88 node->get_parameter(name_ +
"." +
"mark_threshold", mark_threshold_);
89 node->get_parameter(name_ +
"." +
"combination_method", combination_method_);
90 node->get_parameter(name_ +
"." +
"publish_voxel_map", publish_voxel_);
92 auto custom_qos = rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable();
95 voxel_pub_ = node->create_publisher<nav2_msgs::msg::VoxelGrid>(
96 "voxel_grid", custom_qos);
97 voxel_pub_->on_activate();
100 clearing_endpoints_pub_ = node->create_publisher<sensor_msgs::msg::PointCloud2>(
101 "clearing_endpoints", custom_qos);
102 clearing_endpoints_pub_->on_activate();
104 unknown_threshold_ += (VOXEL_BITS - size_z_);
108 dyn_params_handler_ = node->add_on_set_parameters_callback(
111 this, std::placeholders::_1));
116 dyn_params_handler_.reset();
121 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
123 voxel_grid_.
resize(size_x_, size_y_, size_z_);
124 assert(voxel_grid_.sizeX() == size_x_ && voxel_grid_.sizeY() == size_y_);
145 double robot_x,
double robot_y,
double robot_yaw,
double * min_x,
146 double * min_y,
double * max_x,
double * max_y)
148 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
150 if (rolling_window_) {
156 useExtraBounds(min_x, min_y, max_x, max_y);
159 std::vector<Observation> observations, clearing_observations;
171 for (
unsigned int i = 0; i < clearing_observations.size(); ++i) {
176 for (std::vector<Observation>::const_iterator it = observations.begin(); it != observations.end();
181 const sensor_msgs::msg::PointCloud2 & cloud = *(obs.cloud_);
183 double sq_obstacle_max_range = obs.obstacle_max_range_ * obs.obstacle_max_range_;
184 double sq_obstacle_min_range = obs.obstacle_min_range_ * obs.obstacle_min_range_;
186 sensor_msgs::PointCloud2ConstIterator<float> iter_x(cloud,
"x");
187 sensor_msgs::PointCloud2ConstIterator<float> iter_y(cloud,
"y");
188 sensor_msgs::PointCloud2ConstIterator<float> iter_z(cloud,
"z");
190 for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) {
197 double sq_dist = (*iter_x - obs.origin_.x) * (*iter_x - obs.origin_.x) +
198 (*iter_y - obs.origin_.y) * (*iter_y - obs.origin_.y) +
199 (*iter_z - obs.origin_.z) * (*iter_z - obs.origin_.z);
202 if (sq_dist >= sq_obstacle_max_range) {
207 if (sq_dist < sq_obstacle_min_range) {
212 unsigned int mx, my, mz;
213 if (*iter_z < origin_z_) {
214 if (!
worldToMap3D(*iter_x, *iter_y, origin_z_, mx, my, mz)) {
217 }
else if (!
worldToMap3D(*iter_x, *iter_y, *iter_z, mx, my, mz)) {
222 if (voxel_grid_.markVoxelInMap(mx, my, mz, mark_threshold_)) {
223 unsigned int index =
getIndex(mx, my);
225 costmap_[index] = LETHAL_OBSTACLE;
227 static_cast<double>(*iter_x),
static_cast<double>(*iter_y),
228 min_x, min_y, max_x, max_y);
233 if (publish_voxel_) {
234 auto grid_msg = std::make_unique<nav2_msgs::msg::VoxelGrid>();
235 unsigned int size = voxel_grid_.sizeX() * voxel_grid_.sizeY();
236 grid_msg->size_x = voxel_grid_.sizeX();
237 grid_msg->size_y = voxel_grid_.sizeY();
238 grid_msg->size_z = voxel_grid_.sizeZ();
239 grid_msg->data.resize(size);
240 memcpy(&grid_msg->data[0], voxel_grid_.getData(), size *
sizeof(
unsigned int));
242 grid_msg->origin.x = origin_x_;
243 grid_msg->origin.y = origin_y_;
244 grid_msg->origin.z = origin_z_;
246 grid_msg->resolutions.x = resolution_;
247 grid_msg->resolutions.y = resolution_;
248 grid_msg->resolutions.z = z_resolution_;
250 grid_msg->header.stamp = clock_->now();
252 voxel_pub_->publish(std::move(grid_msg));
255 updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
259 const Observation & clearing_observation,
double * min_x,
264 auto clearing_endpoints_ = std::make_unique<sensor_msgs::msg::PointCloud2>();
266 if (clearing_observation.cloud_->height == 0 || clearing_observation.cloud_->width == 0) {
270 double sensor_x, sensor_y, sensor_z;
271 double ox = clearing_observation.origin_.x;
272 double oy = clearing_observation.origin_.y;
273 double oz = clearing_observation.origin_.z;
278 "Sensor origin at (%.2f, %.2f %.2f) is out of map bounds "
279 "(%.2f, %.2f, %.2f) to (%.2f, %.2f, %.2f). "
280 "The costmap cannot raytrace for it.",
282 origin_x_, origin_y_, origin_z_,
289 bool publish_clearing_points;
292 auto node = node_.lock();
294 throw std::runtime_error{
"Failed to lock node"};
296 publish_clearing_points = (node->count_subscribers(
"clearing_endpoints") > 0);
299 clearing_endpoints_->data.clear();
300 clearing_endpoints_->width = clearing_observation.cloud_->width;
301 clearing_endpoints_->height = clearing_observation.cloud_->height;
302 clearing_endpoints_->is_dense =
true;
303 clearing_endpoints_->is_bigendian =
false;
305 sensor_msgs::PointCloud2Modifier modifier(*clearing_endpoints_);
306 modifier.setPointCloud2Fields(
307 3,
"x", 1, sensor_msgs::msg::PointField::FLOAT32,
308 "y", 1, sensor_msgs::msg::PointField::FLOAT32,
309 "z", 1, sensor_msgs::msg::PointField::FLOAT32);
311 sensor_msgs::PointCloud2Iterator<float> clearing_endpoints_iter_x(*clearing_endpoints_,
"x");
312 sensor_msgs::PointCloud2Iterator<float> clearing_endpoints_iter_y(*clearing_endpoints_,
"y");
313 sensor_msgs::PointCloud2Iterator<float> clearing_endpoints_iter_z(*clearing_endpoints_,
"z");
320 sensor_msgs::PointCloud2ConstIterator<float> iter_x(*(clearing_observation.cloud_),
"x");
321 sensor_msgs::PointCloud2ConstIterator<float> iter_y(*(clearing_observation.cloud_),
"y");
322 sensor_msgs::PointCloud2ConstIterator<float> iter_z(*(clearing_observation.cloud_),
"z");
324 for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) {
325 double wpx = *iter_x;
326 double wpy = *iter_y;
327 double wpz = *iter_z;
329 double distance =
dist(ox, oy, oz, wpx, wpy, wpz);
330 double scaling_fact = 1.0;
331 scaling_fact = std::max(std::min(scaling_fact, (distance - 2 * resolution_) / distance), 0.0);
332 wpx = scaling_fact * (wpx - ox) + ox;
333 wpy = scaling_fact * (wpy - oy) + oy;
334 wpz = scaling_fact * (wpz - oz) + oz;
342 if (wpz > map_end_z) {
344 t = std::max(0.0, std::min(t, (map_end_z - 0.01 - oz) / c));
345 }
else if (wpz < origin_z_) {
348 t = std::min(t, (origin_z_ - oz) / c);
352 if (wpx < origin_x_) {
353 t = std::min(t, (origin_x_ - ox) / a);
355 if (wpy < origin_y_) {
356 t = std::min(t, (origin_y_ - oy) / b);
360 if (wpx > map_end_x) {
361 t = std::min(t, (map_end_x - ox) / a);
363 if (wpy > map_end_y) {
364 t = std::min(t, (map_end_y - oy) / b);
371 double point_x, point_y, point_z;
373 unsigned int cell_raytrace_max_range =
cellDistance(clearing_observation.raytrace_max_range_);
374 unsigned int cell_raytrace_min_range =
cellDistance(clearing_observation.raytrace_min_range_);
378 voxel_grid_.clearVoxelLineInMap(
379 sensor_x, sensor_y, sensor_z, point_x, point_y, point_z,
381 unknown_threshold_, mark_threshold_, FREE_SPACE, NO_INFORMATION,
382 cell_raytrace_max_range, cell_raytrace_min_range);
385 ox, oy, wpx, wpy, clearing_observation.raytrace_max_range_,
386 clearing_observation.raytrace_min_range_, min_x, min_y,
390 if (publish_clearing_points) {
391 *clearing_endpoints_iter_x = wpx;
392 *clearing_endpoints_iter_y = wpy;
393 *clearing_endpoints_iter_z = wpz;
395 ++clearing_endpoints_iter_x;
396 ++clearing_endpoints_iter_y;
397 ++clearing_endpoints_iter_z;
402 if (publish_clearing_points) {
404 clearing_endpoints_->header.stamp = clearing_observation.cloud_->header.stamp;
406 clearing_endpoints_pub_->publish(std::move(clearing_endpoints_));
413 int cell_ox, cell_oy;
414 cell_ox =
static_cast<int>((new_origin_x - origin_x_) / resolution_);
415 cell_oy =
static_cast<int>((new_origin_y - origin_y_) / resolution_);
419 double new_grid_ox, new_grid_oy;
420 new_grid_ox = origin_x_ + cell_ox * resolution_;
421 new_grid_oy = origin_y_ + cell_oy * resolution_;
424 int size_x = size_x_;
425 int size_y = size_y_;
428 int lower_left_x, lower_left_y, upper_right_x, upper_right_y;
429 lower_left_x = std::min(std::max(cell_ox, 0), size_x);
430 lower_left_y = std::min(std::max(cell_oy, 0), size_y);
431 upper_right_x = std::min(std::max(cell_ox + size_x, 0), size_x);
432 upper_right_y = std::min(std::max(cell_oy + size_y, 0), size_y);
434 unsigned int cell_size_x = upper_right_x - lower_left_x;
435 unsigned int cell_size_y = upper_right_y - lower_left_y;
438 unsigned char * local_map =
new unsigned char[cell_size_x * cell_size_y];
439 unsigned int * local_voxel_map =
new unsigned int[cell_size_x * cell_size_y];
440 unsigned int * voxel_map = voxel_grid_.getData();
444 costmap_, lower_left_x, lower_left_y, size_x_, local_map, 0, 0, cell_size_x,
448 voxel_map, lower_left_x, lower_left_y, size_x_, local_voxel_map, 0, 0, cell_size_x,
456 origin_x_ = new_grid_ox;
457 origin_y_ = new_grid_oy;
460 int start_x = lower_left_x - cell_ox;
461 int start_y = lower_left_y - cell_oy;
465 local_map, 0, 0, cell_size_x, costmap_, start_x, start_y, size_x_, cell_size_x,
468 local_voxel_map, 0, 0, cell_size_x, voxel_map, start_x, start_y, size_x_,
474 delete[] local_voxel_map;
481 rcl_interfaces::msg::SetParametersResult
483 std::vector<rclcpp::Parameter> parameters)
485 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
486 rcl_interfaces::msg::SetParametersResult result;
487 bool resize_map_needed =
false;
489 for (
auto parameter : parameters) {
490 const auto & param_type = parameter.get_type();
491 const auto & param_name = parameter.get_name();
493 if (param_type == ParameterType::PARAMETER_DOUBLE) {
494 if (param_name == name_ +
"." +
"max_obstacle_height") {
496 }
else if (param_name == name_ +
"." +
"origin_z") {
497 origin_z_ = parameter.as_double();
498 resize_map_needed =
true;
499 }
else if (param_name == name_ +
"." +
"z_resolution") {
500 z_resolution_ = parameter.as_double();
501 resize_map_needed =
true;
503 }
else if (param_type == ParameterType::PARAMETER_BOOL) {
504 if (param_name == name_ +
"." +
"enabled") {
505 enabled_ = parameter.as_bool();
507 }
else if (param_name == name_ +
"." +
"footprint_clearing_enabled") {
508 footprint_clearing_enabled_ = parameter.as_bool();
509 }
else if (param_name == name_ +
"." +
"publish_voxel_map") {
511 logger_,
"publish voxel map is not a dynamic parameter "
512 "cannot be changed while running. Rejecting parameter update.");
516 }
else if (param_type == ParameterType::PARAMETER_INTEGER) {
517 if (param_name == name_ +
"." +
"z_voxels") {
518 size_z_ = parameter.as_int();
519 resize_map_needed =
true;
520 }
else if (param_name == name_ +
"." +
"unknown_threshold") {
521 unknown_threshold_ = parameter.as_int() + (VOXEL_BITS - size_z_);
522 }
else if (param_name == name_ +
"." +
"mark_threshold") {
523 mark_threshold_ = parameter.as_int();
524 }
else if (param_name == name_ +
"." +
"combination_method") {
525 combination_method_ = parameter.as_int();
530 if (resize_map_needed) {
534 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.
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 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.