nonpersistent_voxel_layer.cpp
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  *********************************************************************/
42 
43 #define VOXEL_BITS 16
45 
49 
52 
53 namespace costmap_2d
54 {
55 
57 {
59  ros::NodeHandle private_nh("~/" + name_);
60 
61  private_nh.param("publish_voxel_map", publish_voxel_, false);
62  private_nh.param("footprint_clearing_enabled", footprint_clearing_enabled_, true);
63  if (publish_voxel_)
64  voxel_pub_ = private_nh.advertise < costmap_2d::VoxelGrid > ("voxel_grid", 1);
65 }
66 
68 {
69  voxel_dsrv_ = new dynamic_reconfigure::Server<costmap_2d::NonPersistentVoxelPluginConfig>(nh);
70  dynamic_reconfigure::Server<costmap_2d::NonPersistentVoxelPluginConfig>::CallbackType cb = boost::bind(
72  voxel_dsrv_->setCallback(cb);
73 }
74 
76 {
77  if (voxel_dsrv_)
78  delete voxel_dsrv_;
79 }
80 
81 void NonPersistentVoxelLayer::reconfigureCB(costmap_2d::NonPersistentVoxelPluginConfig &config, uint32_t level)
82 {
83  enabled_ = config.enabled;
84  max_obstacle_height_ = config.max_obstacle_height;
85  size_z_ = config.z_voxels;
86  origin_z_ = config.origin_z;
87  z_resolution_ = config.z_resolution;
88  unknown_threshold_ = config.unknown_threshold + (VOXEL_BITS - size_z_);
89  mark_threshold_ = config.mark_threshold;
90  combination_method_ = config.combination_method;
91  matchSize();
92 }
93 
94 void NonPersistentVoxelLayer::updateFootprint(double robot_x, double robot_y, double robot_yaw, double* min_x, double* min_y,
95  double* max_x, double* max_y)
96 {
98  return;
99  transformFootprint(robot_x, robot_y, robot_yaw, getFootprint(), transformed_footprint_);
100 
101  for (unsigned int i = 0; i < transformed_footprint_.size(); i++)
102  {
103  touch(transformed_footprint_[i].x, transformed_footprint_[i].y, min_x, min_y, max_x, max_y);
104  }
105 
107 }
108 
109 
111 {
115 }
116 
118 {
119  deactivate();
120  resetMaps();
121  voxel_grid_.reset();
122  activate();
123 }
124 
126 {
128  voxel_grid_.reset();
129 }
130 
131 void NonPersistentVoxelLayer::updateBounds(double robot_x, double robot_y, double robot_yaw, double* min_x,
132  double* min_y, double* max_x, double* max_y)
133 {
134  // update origin information for rolling costmap publication
135  if (rolling_window_)
136  {
137  updateOrigin(robot_x - getSizeInMetersX() / 2, robot_y - getSizeInMetersY() / 2);
138  }
139 
140  // reset maps each iteration
141  resetMaps();
142 
143  // if not enabled, stop here
144  if (!enabled_)
145  return;
146 
147  // get the maximum sized window required to operate
148  useExtraBounds(min_x, min_y, max_x, max_y);
149 
150  // get the marking observations
151  bool current = true;
152  std::vector<Observation> observations;
153  current = getMarkingObservations(observations) && current;
154 
155  // update the global current status
156  current_ = current;
157 
158  // place the new obstacles into a priority queue... each with a priority of zero to begin with
159  for (std::vector<Observation>::const_iterator it = observations.begin(); it != observations.end(); ++it)
160  {
161  const Observation& obs = *it;
162 
163  double sq_obstacle_range = obs.obstacle_range_ * obs.obstacle_range_;
164 
168  for (; it_x != it_x.end(); ++it_x, ++it_y, ++it_z)
169  {
170  // if the obstacle is too high or too far away from the robot we won't add it
171  if (*it_z > max_obstacle_height_)
172  continue;
173 
174  // compute the squared distance from the hitpoint to the pointcloud's origin
175  double sq_dist = (*it_x - obs.origin_.x) * (*it_x - obs.origin_.x)
176  + (*it_y - obs.origin_.y) * (*it_y - obs.origin_.y)
177  + (*it_z - obs.origin_.z) * (*it_z - obs.origin_.z);
178 
179  // if the point is far enough away... we won't consider it
180  if (sq_dist >= sq_obstacle_range)
181  continue;
182 
183  // now we need to compute the map coordinates for the observation
184  unsigned int mx, my, mz;
185  if (*it_z < origin_z_)
186  {
187  if (!worldToMap3D(*it_x, *it_y, origin_z_, mx, my, mz))
188  continue;
189  }
190  else if (!worldToMap3D(*it_x, *it_y, *it_z, mx, my, mz))
191  {
192  continue;
193  }
194 
195  // mark the cell in the voxel grid and check if we should also mark it in the costmap
196  if (voxel_grid_.markVoxelInMap(mx, my, mz, mark_threshold_))
197  {
198  unsigned int index = getIndex(mx, my);
199 
200  costmap_[index] = LETHAL_OBSTACLE;
201  touch((double)*it_x, (double)*it_y, min_x, min_y, max_x, max_y);
202  }
203  }
204  }
205 
206  if (publish_voxel_)
207  {
208  costmap_2d::VoxelGrid grid_msg;
209  unsigned int size = voxel_grid_.sizeX() * voxel_grid_.sizeY();
210  grid_msg.size_x = voxel_grid_.sizeX();
211  grid_msg.size_y = voxel_grid_.sizeY();
212  grid_msg.size_z = voxel_grid_.sizeZ();
213  grid_msg.data.resize(size);
214  memcpy(&grid_msg.data[0], voxel_grid_.getData(), size * sizeof(unsigned int));
215 
216  grid_msg.origin.x = origin_x_;
217  grid_msg.origin.y = origin_y_;
218  grid_msg.origin.z = origin_z_;
219 
220  grid_msg.resolutions.x = resolution_;
221  grid_msg.resolutions.y = resolution_;
222  grid_msg.resolutions.z = z_resolution_;
223  grid_msg.header.frame_id = global_frame_;
224  grid_msg.header.stamp = ros::Time::now();
225  voxel_pub_.publish(grid_msg);
226  }
227 
228  updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
229 }
230 
231 void NonPersistentVoxelLayer::updateOrigin(double new_origin_x, double new_origin_y)
232 {
233  // project the new origin into the grid
234  int cell_ox, cell_oy;
235  cell_ox = int((new_origin_x - origin_x_) / resolution_);
236  cell_oy = int((new_origin_y - origin_y_) / resolution_);
237 
238  // update the origin with the appropriate world coordinates
239  origin_x_ = origin_x_ + cell_ox * resolution_;
240  origin_y_ = origin_y_ + cell_oy * resolution_;
241 }
242 
243 } // namespace costmap_2d
costmap_2d::Costmap2D::getSizeInMetersX
double getSizeInMetersX() const
costmap_2d::ObstacleLayer::deactivate
virtual void deactivate()
costmap_2d::ObstacleLayer::getMarkingObservations
bool getMarkingObservations(std::vector< costmap_2d::Observation > &marking_observations) const
point_cloud2_iterator.h
costmap_2d::transformFootprint
void transformFootprint(double x, double y, double theta, const std::vector< geometry_msgs::Point > &footprint_spec, geometry_msgs::PolygonStamped &oriented_footprint)
costmap_2d::ObstacleLayer::global_frame_
std::string global_frame_
nonpersistent_voxel_layer.hpp
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::Layer::enabled_
bool enabled_
PointCloud2IteratorBase< T, const T, const unsigned char, const sensor_msgs::PointCloud2, PointCloud2ConstIterator >::end
PointCloud2ConstIterator< T > end() const
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
voxel_grid::VoxelGrid::sizeZ
unsigned int sizeZ()
costmap_2d::Costmap2D::getSizeInMetersY
double getSizeInMetersY() const
costmap_2d::NonPersistentVoxelLayer::~NonPersistentVoxelLayer
virtual ~NonPersistentVoxelLayer()
Definition: nonpersistent_voxel_layer.cpp:75
costmap_2d::NO_INFORMATION
static const unsigned char NO_INFORMATION
costmap_2d::Costmap2D::origin_x_
double origin_x_
costmap_2d::CostmapLayer::matchSize
virtual void matchSize()
VOXEL_BITS
#define VOXEL_BITS
Definition: nonpersistent_voxel_layer.cpp:43
costmap_2d::NonPersistentVoxelLayer::matchSize
virtual void matchSize()
Definition: nonpersistent_voxel_layer.cpp:110
voxel_grid::VoxelGrid::sizeX
unsigned int sizeX()
costmap_2d::Layer::name_
std::string name_
costmap_2d::Layer::current_
bool current_
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
sensor_msgs::PointCloud2ConstIterator
costmap_2d::ObstacleLayer::onInitialize
virtual void onInitialize()
costmap_2d::NonPersistentVoxelLayer::resetMaps
virtual void resetMaps()
Definition: nonpersistent_voxel_layer.cpp:125
costmap_2d::Observation::cloud_
sensor_msgs::PointCloud2 * cloud_
voxel_grid::VoxelGrid::sizeY
unsigned int sizeY()
class_list_macros.h
costmap_2d::NonPersistentVoxelLayer::setupDynamicReconfigure
virtual void setupDynamicReconfigure(ros::NodeHandle &nh)
Definition: nonpersistent_voxel_layer.cpp:67
costmap_2d::ObstacleLayer::max_obstacle_height_
double max_obstacle_height_
voxel_grid::VoxelGrid::reset
void reset()
costmap_2d::NonPersistentVoxelLayer::voxel_dsrv_
dynamic_reconfigure::Server< costmap_2d::NonPersistentVoxelPluginConfig > * voxel_dsrv_
Definition: nonpersistent_voxel_layer.hpp:170
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
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
voxel_grid::VoxelGrid::resize
void resize(unsigned int size_x, unsigned int size_y, unsigned int size_z)
costmap_2d::ObstacleLayer::activate
virtual void activate()
costmap_2d::NonPersistentVoxelLayer::size_z_
unsigned int size_z_
Definition: nonpersistent_voxel_layer.hpp:176
costmap_2d::ObstacleLayer::combination_method_
int combination_method_
costmap_2d::ObstacleLayer::transformed_footprint_
std::vector< geometry_msgs::Point > transformed_footprint_
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
Definition: nonpersistent_voxel_layer.hpp:100
costmap_2d::LETHAL_OBSTACLE
static const unsigned char LETHAL_OBSTACLE
costmap_2d::Observation::obstacle_range_
double obstacle_range_
costmap_2d::Layer::getFootprint
const std::vector< geometry_msgs::Point > & getFootprint() const
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::CostmapLayer::useExtraBounds
void useExtraBounds(double *min_x, double *min_y, double *max_x, double *max_y)
voxel_grid::VoxelGrid::getData
uint32_t * getData()
costmap_2d::Costmap2D::size_x_
unsigned int size_x_
costmap_2d::NonPersistentVoxelLayer::mark_threshold_
unsigned int mark_threshold_
Definition: nonpersistent_voxel_layer.hpp:176
costmap_2d::NonPersistentVoxelLayer::reconfigureCB
void reconfigureCB(costmap_2d::NonPersistentVoxelPluginConfig &config, uint32_t level)
Definition: nonpersistent_voxel_layer.cpp:81
costmap_2d::CostmapLayer::touch
void touch(double x, double y, double *min_x, double *min_y, double *max_x, double *max_y)
costmap_2d::Costmap2D::resolution_
double resolution_
costmap_2d::Observation
costmap_2d::Costmap2D::resetMaps
virtual void resetMaps()
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
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::Layer
costmap_2d::Observation::origin_
geometry_msgs::Point origin_
costmap_2d::Costmap2D::setConvexPolygonCost
bool setConvexPolygonCost(const std::vector< geometry_msgs::Point > &polygon, unsigned char cost_value)
costmap_2d::Costmap2D::getIndex
unsigned int getIndex(unsigned int mx, unsigned int my) const
costmap_2d::Costmap2D::costmap_
unsigned char * costmap_
costmap_2d::FREE_SPACE
static const unsigned char FREE_SPACE
voxel_grid::VoxelGrid::markVoxelInMap
bool markVoxelInMap(unsigned int x, unsigned int y, unsigned int z, unsigned int marked_threshold)
ROS_ASSERT
#define ROS_ASSERT(cond)
costmap_2d::ObstacleLayer::footprint_clearing_enabled_
bool footprint_clearing_enabled_
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
costmap_2d::ObservationBuffer
costmap_2d::ObstacleLayer::rolling_window_
bool rolling_window_
ros::NodeHandle
ros::Time::now
static Time now()


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