Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
voxel_layer.hpp
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, 2013, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Eitan Marder-Eppstein
36  * David V. Lu!!
37  *********************************************************************/
38 #ifndef NAV2_COSTMAP_2D__VOXEL_LAYER_HPP_
39 #define NAV2_COSTMAP_2D__VOXEL_LAYER_HPP_
40 
41 #include <vector>
42 #include "message_filters/subscriber.h"
43 
44 #include <rclcpp/rclcpp.hpp>
45 #include <nav2_costmap_2d/layer.hpp>
46 #include <nav2_costmap_2d/layered_costmap.hpp>
47 #include <nav2_costmap_2d/observation_buffer.hpp>
48 #include <nav_msgs/msg/occupancy_grid.hpp>
49 #include <nav2_msgs/msg/voxel_grid.hpp>
50 #include <sensor_msgs/msg/laser_scan.hpp>
51 #include <laser_geometry/laser_geometry.hpp>
52 #include <sensor_msgs/msg/point_cloud.hpp>
53 #include <sensor_msgs/msg/point_cloud2.hpp>
54 #include <nav2_costmap_2d/obstacle_layer.hpp>
55 #include <nav2_voxel_grid/voxel_grid.hpp>
56 
57 namespace nav2_costmap_2d
58 {
59 
64 class VoxelLayer : public ObstacleLayer
65 {
66 public:
71  : voxel_grid_(0, 0, 0)
72  {
73  costmap_ = NULL; // this is the unsigned char* member of parent class's parent class Costmap2D
74  }
75 
79  virtual ~VoxelLayer();
80 
84  virtual void onInitialize();
85 
96  virtual void updateBounds(
97  double robot_x, double robot_y, double robot_yaw, double * min_x,
98  double * min_y,
99  double * max_x,
100  double * max_y);
101 
105  void updateOrigin(double new_origin_x, double new_origin_y);
106 
111  {
112  return true;
113  }
114 
118  virtual void matchSize();
119 
123  virtual void reset();
124 
128  virtual bool isClearable() {return true;}
129 
130 protected:
134  virtual void resetMaps();
135 
139  virtual void raytraceFreespace(
140  const nav2_costmap_2d::Observation & clearing_observation,
141  double * min_x, double * min_y,
142  double * max_x,
143  double * max_y);
144 
145  bool publish_voxel_;
146  rclcpp_lifecycle::LifecyclePublisher<nav2_msgs::msg::VoxelGrid>::SharedPtr voxel_pub_;
147  nav2_voxel_grid::VoxelGrid voxel_grid_;
148  double z_resolution_, origin_z_;
149  int unknown_threshold_, mark_threshold_, size_z_;
150  rclcpp_lifecycle::LifecyclePublisher<sensor_msgs::msg::PointCloud2>::SharedPtr
151  clearing_endpoints_pub_;
152 
156  inline bool worldToMap3DFloat(
157  double wx, double wy, double wz, double & mx, double & my,
158  double & mz)
159  {
160  if (wx < origin_x_ || wy < origin_y_ || wz < origin_z_) {
161  return false;
162  }
163  mx = ((wx - origin_x_) / resolution_);
164  my = ((wy - origin_y_) / resolution_);
165  mz = ((wz - origin_z_) / z_resolution_);
166  if (mx < size_x_ && my < size_y_ && mz < size_z_) {
167  return true;
168  }
169 
170  return false;
171  }
172 
176  inline bool worldToMap3D(
177  double wx, double wy, double wz, unsigned int & mx, unsigned int & my,
178  unsigned int & mz)
179  {
180  if (wx < origin_x_ || wy < origin_y_ || wz < origin_z_) {
181  return false;
182  }
183 
184  mx = static_cast<unsigned int>((wx - origin_x_) / resolution_);
185  my = static_cast<unsigned int>((wy - origin_y_) / resolution_);
186  mz = static_cast<unsigned int>((wz - origin_z_) / z_resolution_);
187 
188  if (mx < size_x_ && my < size_y_ && mz < (unsigned int)size_z_) {
189  return true;
190  }
191 
192  return false;
193  }
194 
198  inline void mapToWorld3D(
199  unsigned int mx, unsigned int my, unsigned int mz, double & wx,
200  double & wy,
201  double & wz)
202  {
203  // returns the center point of the cell
204  wx = origin_x_ + (mx + 0.5) * resolution_;
205  wy = origin_y_ + (my + 0.5) * resolution_;
206  wz = origin_z_ + (mz + 0.5) * z_resolution_;
207  }
208 
212  inline double dist(double x0, double y0, double z0, double x1, double y1, double z1)
213  {
214  return sqrt((x1 - x0) * (x1 - x0) + (y1 - y0) * (y1 - y0) + (z1 - z0) * (z1 - z0));
215  }
216 
220  double getSizeInMetersZ() const
221  {
222  return (size_z_ - 1 + 0.5) * z_resolution_;
223  }
224 
229  rcl_interfaces::msg::SetParametersResult
230  dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
231 
232  // Dynamic parameters handler
233  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
234 };
235 
236 } // namespace nav2_costmap_2d
237 
238 #endif // NAV2_COSTMAP_2D__VOXEL_LAYER_HPP_
Stores an observation in terms of a point cloud and the origin of the source.
Definition: observation.hpp:47
Takes in laser and pointcloud data to populate into 2D costmap.
Takes laser and pointcloud data to populate a 3D voxel representation of the environment.
Definition: voxel_layer.hpp:65
void mapToWorld3D(unsigned int mx, unsigned int my, unsigned int mz, double &wx, double &wy, double &wz)
Covert map coordinates into world coordinates.
virtual void onInitialize()
Initialization process of layer on startup.
Definition: voxel_layer.cpp:61
virtual ~VoxelLayer()
Voxel Layer destructor.
double getSizeInMetersZ() const
Get the height of the voxel sizes in meters.
virtual bool isClearable()
If clearing operations should be processed on this layer or not.
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.
VoxelLayer()
Voxel Layer constructor.
Definition: voxel_layer.hpp:70
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.
bool isDiscretized()
If layer is discretely populated.