Nav2 Navigation Stack - kilted  kilted
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 
43 #include <rclcpp/rclcpp.hpp>
44 #include <nav2_costmap_2d/layer.hpp>
45 #include <nav2_costmap_2d/layered_costmap.hpp>
46 #include <nav2_costmap_2d/observation_buffer.hpp>
47 #include <nav_msgs/msg/occupancy_grid.hpp>
48 #include <nav2_msgs/msg/voxel_grid.hpp>
49 #include <sensor_msgs/msg/laser_scan.hpp>
50 #include <laser_geometry/laser_geometry.hpp>
51 #include <sensor_msgs/msg/point_cloud.hpp>
52 #include <sensor_msgs/msg/point_cloud2.hpp>
53 #include <nav2_costmap_2d/obstacle_layer.hpp>
54 #include <nav2_voxel_grid/voxel_grid.hpp>
55 
56 namespace nav2_costmap_2d
57 {
58 
63 class VoxelLayer : public ObstacleLayer
64 {
65 public:
70  : voxel_grid_(0, 0, 0)
71  {
72  costmap_ = NULL; // this is the unsigned char* member of parent class's parent class Costmap2D
73  }
74 
78  virtual ~VoxelLayer();
79 
83  virtual void onInitialize();
84 
95  virtual void updateBounds(
96  double robot_x, double robot_y, double robot_yaw, double * min_x,
97  double * min_y,
98  double * max_x,
99  double * max_y);
100 
104  void updateOrigin(double new_origin_x, double new_origin_y);
105 
110  {
111  return true;
112  }
113 
117  virtual void matchSize();
118 
122  virtual void reset();
123 
127  virtual bool isClearable() {return true;}
128 
129 protected:
133  virtual void resetMaps();
134 
138  virtual void raytraceFreespace(
139  const nav2_costmap_2d::Observation & clearing_observation,
140  double * min_x, double * min_y,
141  double * max_x,
142  double * max_y);
143 
144  bool publish_voxel_;
145  rclcpp_lifecycle::LifecyclePublisher<nav2_msgs::msg::VoxelGrid>::SharedPtr voxel_pub_;
146  nav2_voxel_grid::VoxelGrid voxel_grid_;
147  double z_resolution_, origin_z_;
148  int unknown_threshold_, mark_threshold_, size_z_;
149  rclcpp_lifecycle::LifecyclePublisher<sensor_msgs::msg::PointCloud2>::SharedPtr
150  clearing_endpoints_pub_;
151 
155  inline bool worldToMap3DFloat(
156  double wx, double wy, double wz, double & mx, double & my,
157  double & mz)
158  {
159  if (wx < origin_x_ || wy < origin_y_ || wz < origin_z_) {
160  return false;
161  }
162  mx = ((wx - origin_x_) / resolution_);
163  my = ((wy - origin_y_) / resolution_);
164  mz = ((wz - origin_z_) / z_resolution_);
165  if (mx < size_x_ && my < size_y_ && mz < size_z_) {
166  return true;
167  }
168 
169  return false;
170  }
171 
175  inline bool worldToMap3D(
176  double wx, double wy, double wz, unsigned int & mx, unsigned int & my,
177  unsigned int & mz)
178  {
179  if (wx < origin_x_ || wy < origin_y_ || wz < origin_z_) {
180  return false;
181  }
182 
183  mx = static_cast<unsigned int>((wx - origin_x_) / resolution_);
184  my = static_cast<unsigned int>((wy - origin_y_) / resolution_);
185  mz = static_cast<unsigned int>((wz - origin_z_) / z_resolution_);
186 
187  if (mx < size_x_ && my < size_y_ && mz < (unsigned int)size_z_) {
188  return true;
189  }
190 
191  return false;
192  }
193 
197  inline void mapToWorld3D(
198  unsigned int mx, unsigned int my, unsigned int mz, double & wx,
199  double & wy,
200  double & wz)
201  {
202  // returns the center point of the cell
203  wx = origin_x_ + (mx + 0.5) * resolution_;
204  wy = origin_y_ + (my + 0.5) * resolution_;
205  wz = origin_z_ + (mz + 0.5) * z_resolution_;
206  }
207 
211  inline double dist(double x0, double y0, double z0, double x1, double y1, double z1)
212  {
213  return sqrt((x1 - x0) * (x1 - x0) + (y1 - y0) * (y1 - y0) + (z1 - z0) * (z1 - z0));
214  }
215 
219  double getSizeInMetersZ() const
220  {
221  return (size_z_ - 1 + 0.5) * z_resolution_;
222  }
223 
228  rcl_interfaces::msg::SetParametersResult
229  dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
230 
231  // Dynamic parameters handler
232  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
233 };
234 
235 } // namespace nav2_costmap_2d
236 
237 #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:64
void mapToWorld3D(unsigned int mx, unsigned int my, unsigned int mz, double &wx, double &wy, double &wz)
Convert 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)
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.
VoxelLayer()
Voxel Layer constructor.
Definition: voxel_layer.hpp:69
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.