nonpersistent_voxel_layer.hpp
Go to the documentation of this file.
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  * Steve Macenski
38  *********************************************************************/
39 #ifndef COSTMAP_2D_NONPERSISTENT_VOXEL_LAYER_H_
40 #define COSTMAP_2D_NONPERSISTENT_VOXEL_LAYER_H_
41 
42 #include <ros/ros.h>
43 #include <costmap_2d/layer.h>
46 #include <costmap_2d/VoxelGrid.h>
47 #include <nav_msgs/OccupancyGrid.h>
48 #include <sensor_msgs/LaserScan.h>
50 #include <sensor_msgs/PointCloud.h>
51 #include <sensor_msgs/PointCloud2.h>
53 #include <tf/message_filter.h>
55 #include <dynamic_reconfigure/server.h>
56 #include <nonpersistent_voxel_layer/NonPersistentVoxelPluginConfig.h>
58 #include <voxel_grid/voxel_grid.h>
59 
60 namespace costmap_2d
61 {
62 
63 class NonPersistentVoxelLayer : public ObstacleLayer
64 {
65 public:
67  voxel_grid_(0, 0, 0)
68  {
69  costmap_ = NULL; // this is the unsigned char* member of parent class's parent class Costmap2D.
70  }
71 
72  virtual ~NonPersistentVoxelLayer();
73 
74  virtual void onInitialize();
75  virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double* min_x, double* min_y,
76  double* max_x, double* max_y);
77 
78  void updateOrigin(double new_origin_x, double new_origin_y);
79  bool isDiscretized()
80  {
81  return true;
82  }
83  virtual void matchSize();
84  virtual void reset();
85 
86 
87 protected:
88  virtual void setupDynamicReconfigure(ros::NodeHandle& nh);
89  virtual void resetMaps();
90  void updateFootprint(double robot_x, double robot_y, double robot_yaw, double* min_x, double* min_y,
91  double* max_x, double* max_y);
92 
93 private:
94  void reconfigureCB(costmap_2d::NonPersistentVoxelPluginConfig &config, uint32_t level);
95 
96  dynamic_reconfigure::Server<costmap_2d::NonPersistentVoxelPluginConfig> *voxel_dsrv_;
97 
98  bool publish_voxel_;
101  double z_resolution_, origin_z_;
103 
104  inline bool worldToMap3DFloat(double wx, double wy, double wz, double& mx, double& my, double& mz)
105  {
106  if (wx < origin_x_ || wy < origin_y_ || wz < origin_z_)
107  return false;
108  mx = ((wx - origin_x_) / resolution_);
109  my = ((wy - origin_y_) / resolution_);
110  mz = ((wz - origin_z_) / z_resolution_);
111  if (mx < size_x_ && my < size_y_ && mz < size_z_)
112  return true;
113 
114  return false;
115  }
116 
117  inline bool worldToMap3D(double wx, double wy, double wz, unsigned int& mx, unsigned int& my, unsigned int& mz)
118  {
119  if (wx < origin_x_ || wy < origin_y_ || wz < origin_z_)
120  return false;
121 
122  mx = (int)((wx - origin_x_) / resolution_);
123  my = (int)((wy - origin_y_) / resolution_);
124  mz = (int)((wz - origin_z_) / z_resolution_);
125 
126  if (mx < size_x_ && my < size_y_ && mz < size_z_)
127  return true;
128 
129  return false;
130  }
131 
132  inline void mapToWorld3D(unsigned int mx, unsigned int my, unsigned int mz, double& wx, double& wy, double& wz)
133  {
134  // returns the center point of the cell
135  wx = origin_x_ + (mx + 0.5) * resolution_;
136  wy = origin_y_ + (my + 0.5) * resolution_;
137  wz = origin_z_ + (mz + 0.5) * z_resolution_;
138  }
139 
140  inline double dist(double x0, double y0, double z0, double x1, double y1, double z1)
141  {
142  return sqrt((x1 - x0) * (x1 - x0) + (y1 - y0) * (y1 - y0) + (z1 - z0) * (z1 - z0));
143  }
144 };
145 
146 } // namespace costmap_2d
147 
148 #endif // COSTMAP_2D_NONPERSISTENT_VOXEL_LAYER_H_
obstacle_layer.h
ros::Publisher
costmap_2d::NonPersistentVoxelLayer::origin_z_
double origin_z_
Definition: nonpersistent_voxel_layer.hpp:175
costmap_2d::NonPersistentVoxelLayer::updateOrigin
void updateOrigin(double new_origin_x, double new_origin_y)
Definition: nonpersistent_voxel_layer.cpp:231
costmap_2d::NonPersistentVoxelLayer::z_resolution_
double z_resolution_
Definition: nonpersistent_voxel_layer.hpp:175
costmap_2d::NonPersistentVoxelLayer::updateBounds
virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
Definition: nonpersistent_voxel_layer.cpp:131
costmap_2d::NonPersistentVoxelLayer::worldToMap3DFloat
bool worldToMap3DFloat(double wx, double wy, double wz, double &mx, double &my, double &mz)
Definition: nonpersistent_voxel_layer.hpp:178
costmap_2d::NonPersistentVoxelLayer::~NonPersistentVoxelLayer
virtual ~NonPersistentVoxelLayer()
Definition: nonpersistent_voxel_layer.cpp:75
ros.h
voxel_grid.h
costmap_2d::Costmap2D::origin_x_
double origin_x_
layered_costmap.h
costmap_2d::NonPersistentVoxelLayer::matchSize
virtual void matchSize()
Definition: nonpersistent_voxel_layer.cpp:110
costmap_2d::NonPersistentVoxelLayer::dist
double dist(double x0, double y0, double z0, double x1, double y1, double z1)
Definition: nonpersistent_voxel_layer.hpp:214
costmap_2d::NonPersistentVoxelLayer::resetMaps
virtual void resetMaps()
Definition: nonpersistent_voxel_layer.cpp:125
costmap_2d::NonPersistentVoxelLayer::setupDynamicReconfigure
virtual void setupDynamicReconfigure(ros::NodeHandle &nh)
Definition: nonpersistent_voxel_layer.cpp:67
costmap_2d::NonPersistentVoxelLayer::mapToWorld3D
void mapToWorld3D(unsigned int mx, unsigned int my, unsigned int mz, double &wx, double &wy, double &wz)
Definition: nonpersistent_voxel_layer.hpp:206
laser_geometry.h
costmap_2d::NonPersistentVoxelLayer::NonPersistentVoxelLayer
NonPersistentVoxelLayer()
Definition: nonpersistent_voxel_layer.hpp:140
costmap_2d::NonPersistentVoxelLayer::voxel_dsrv_
dynamic_reconfigure::Server< costmap_2d::NonPersistentVoxelPluginConfig > * voxel_dsrv_
Definition: nonpersistent_voxel_layer.hpp:170
message_filter.h
costmap_2d::NonPersistentVoxelLayer::worldToMap3D
bool worldToMap3D(double wx, double wy, double wz, unsigned int &mx, unsigned int &my, unsigned int &mz)
Definition: nonpersistent_voxel_layer.hpp:191
subscriber.h
observation_buffer.h
costmap_2d::NonPersistentVoxelLayer::size_z_
unsigned int size_z_
Definition: nonpersistent_voxel_layer.hpp:176
costmap_2d::NonPersistentVoxelLayer::voxel_pub_
ros::Publisher voxel_pub_
Definition: nonpersistent_voxel_layer.hpp:173
costmap_2d::Costmap2D::size_y_
unsigned int size_y_
costmap_2d::NonPersistentVoxelLayer::onInitialize
virtual void onInitialize()
Definition: nonpersistent_voxel_layer.cpp:56
costmap_2d::NonPersistentVoxelLayer::unknown_threshold_
unsigned int unknown_threshold_
Definition: nonpersistent_voxel_layer.hpp:176
costmap_2d::NonPersistentVoxelLayer::publish_voxel_
bool publish_voxel_
Definition: nonpersistent_voxel_layer.hpp:172
costmap_2d::Costmap2D::size_x_
unsigned int size_x_
layer.h
costmap_2d::NonPersistentVoxelLayer::mark_threshold_
unsigned int mark_threshold_
Definition: nonpersistent_voxel_layer.hpp:176
point_cloud_conversion.h
costmap_2d::NonPersistentVoxelLayer::reconfigureCB
void reconfigureCB(costmap_2d::NonPersistentVoxelPluginConfig &config, uint32_t level)
Definition: nonpersistent_voxel_layer.cpp:81
costmap_2d::Costmap2D::resolution_
double resolution_
costmap_2d::Costmap2D::origin_y_
double origin_y_
costmap_2d::NonPersistentVoxelLayer::reset
virtual void reset()
Definition: nonpersistent_voxel_layer.cpp:117
costmap_2d::NonPersistentVoxelLayer::voxel_grid_
voxel_grid::VoxelGrid voxel_grid_
Definition: nonpersistent_voxel_layer.hpp:174
costmap_2d::Costmap2D::costmap_
unsigned char * costmap_
costmap_2d
costmap_2d::NonPersistentVoxelLayer::updateFootprint
void updateFootprint(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
Definition: nonpersistent_voxel_layer.cpp:94
voxel_grid::VoxelGrid
costmap_2d::NonPersistentVoxelLayer::isDiscretized
bool isDiscretized()
Definition: nonpersistent_voxel_layer.hpp:153
ros::NodeHandle


nonpersistent_voxel_layer
Author(s): Steven Macenski, stevenmacenski@gmail.com
autogenerated on Wed Mar 2 2022 00:37:05