static_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  *********************************************************************/
38 
39 /*
40  * Modified: added "layered_costmap_->updateMap(0,0,0);" below
41  */
42 
43 #include "static_layer.h"
46 
48 
49 using costmap_2d::NO_INFORMATION;
50 using costmap_2d::LETHAL_OBSTACLE;
51 using costmap_2d::FREE_SPACE;
52 
53 namespace rtabmap_ros
54 {
55 
56 StaticLayer::StaticLayer() : dsrv_(NULL) {}
57 
59 {
60  if(dsrv_)
61  delete dsrv_;
62 }
63 
65 {
66  ros::NodeHandle nh("~/" + name_), g_nh;
67  current_ = true;
68 
70 
71  std::string map_topic;
72  nh.param("map_topic", map_topic, std::string("map"));
73  nh.param("subscribe_to_updates", subscribe_to_updates_, false);
74 
75  nh.param("track_unknown_space", track_unknown_space_, true);
76  nh.param("use_maximum", use_maximum_, false);
77 
78  int temp_lethal_threshold, temp_unknown_cost_value;
79  nh.param("lethal_cost_threshold", temp_lethal_threshold, int(100));
80  nh.param("unknown_cost_value", temp_unknown_cost_value, int(-1));
81  nh.param("trinary_costmap", trinary_costmap_, true);
82 
83  lethal_threshold_ = std::max(std::min(temp_lethal_threshold, 100), 0);
84  unknown_cost_value_ = temp_unknown_cost_value;
85  //we'll subscribe to the latched topic that the map server uses
86  ROS_INFO("Requesting the map...");
87  map_sub_ = g_nh.subscribe(map_topic, 1, &StaticLayer::incomingMap, this);
88  map_received_ = false;
89  has_updated_data_ = false;
90 
91  ros::Rate r(10);
92  while (!map_received_ && g_nh.ok())
93  {
94  ros::spinOnce();
95  r.sleep();
96  }
97 
98  ROS_INFO("Received a %d X %d map at %f m/pix", getSizeInCellsX(), getSizeInCellsY(), getResolution());
99 
101  {
102  ROS_INFO("Subscribing to updates");
103  map_update_sub_ = g_nh.subscribe(map_topic + "_updates", 10, &StaticLayer::incomingUpdate, this);
104  }
105 
106  if(dsrv_)
107  {
108  delete dsrv_;
109  }
110 
111  dsrv_ = new dynamic_reconfigure::Server<costmap_2d::GenericPluginConfig>(nh);
112  dynamic_reconfigure::Server<costmap_2d::GenericPluginConfig>::CallbackType cb = boost::bind(
113  &StaticLayer::reconfigureCB, this, _1, _2);
114  dsrv_->setCallback(cb);
115 }
116 
117 void StaticLayer::reconfigureCB(costmap_2d::GenericPluginConfig &config, uint32_t level)
118 {
119  if (config.enabled != enabled_)
120  {
121  enabled_ = config.enabled;
122  has_updated_data_ = true;
123  x_ = y_ = 0;
124  width_ = size_x_;
125  height_ = size_y_;
126  }
127 }
128 
130 {
132  resizeMap(master->getSizeInCellsX(), master->getSizeInCellsY(), master->getResolution(),
133  master->getOriginX(), master->getOriginY());
134 }
135 
136 unsigned char StaticLayer::interpretValue(unsigned char value)
137 {
138  //check if the static value is above the unknown or lethal thresholds
140  return NO_INFORMATION;
141  else if (value >= lethal_threshold_)
142  return LETHAL_OBSTACLE;
143  else if (trinary_costmap_)
144  return FREE_SPACE;
145 
146  double scale = (double) value / lethal_threshold_;
147  return scale * LETHAL_OBSTACLE;
148 }
149 
150 void StaticLayer::incomingMap(const nav_msgs::OccupancyGridConstPtr& new_map)
151 {
152  unsigned int size_x = new_map->info.width, size_y = new_map->info.height;
153 
154  ROS_DEBUG("Received a %d X %d map at %f m/pix", size_x, size_y, new_map->info.resolution);
155 
156  // resize costmap if size, resolution or origin do not match
158  if (master->getSizeInCellsX() != size_x ||
159  master->getSizeInCellsY() != size_y ||
160  master->getResolution() != new_map->info.resolution ||
161  master->getOriginX() != new_map->info.origin.position.x ||
162  master->getOriginY() != new_map->info.origin.position.y ||
164  {
165  ROS_INFO("Resizing costmap to %d X %d at %f m/pix", size_x, size_y, new_map->info.resolution);
166  layered_costmap_->resizeMap(size_x, size_y, new_map->info.resolution, new_map->info.origin.position.x,
167  new_map->info.origin.position.y, true);
168  }else if(size_x_ != size_x || size_y_ != size_y ||
169  resolution_ != new_map->info.resolution ||
170  origin_x_ != new_map->info.origin.position.x ||
171  origin_y_ != new_map->info.origin.position.y){
172  matchSize();
173  }
174 
175  unsigned int index = 0;
176 
177  //initialize the costmap with static data
178  for (unsigned int i = 0; i < size_y; ++i)
179  {
180  for (unsigned int j = 0; j < size_x; ++j)
181  {
182  unsigned char value = new_map->data[index];
183  costmap_[index] = interpretValue(value);
184  ++index;
185  }
186  }
187  x_ = y_ = 0;
188  width_ = size_x_;
189  height_ = size_y_;
190  map_received_ = true;
191  has_updated_data_ = true;
192 
193  layered_costmap_->updateMap(0,0,0);
194 }
195 
196 void StaticLayer::incomingUpdate(const map_msgs::OccupancyGridUpdateConstPtr& update)
197 {
198  unsigned int di = 0;
199  for (unsigned int y = 0; y < update->height ; y++)
200  {
201  unsigned int index_base = (update->y + y) * size_x_;
202  for (unsigned int x = 0; x < update->width ; x++)
203  {
204  unsigned int index = index_base + x + update->x;
205  costmap_[index] = interpretValue( update->data[di++] );
206  }
207  }
208  x_ = update->x;
209  y_ = update->y;
210  width_ = update->width;
211  height_ = update->height;
212  has_updated_data_ = true;
213 
214  layered_costmap_->updateMap(0,0,0);
215 }
216 
218 {
219  onInitialize();
220 }
221 
223 {
224  map_sub_.shutdown();
227 }
228 
230 {
231  deactivate();
232  activate();
233 }
234 
235 void StaticLayer::updateBounds(double robot_x, double robot_y, double robot_yaw, double* min_x, double* min_y,
236  double* max_x, double* max_y)
237 {
239  return;
240 
241  useExtraBounds(min_x, min_y, max_x, max_y);
242 
243  double mx, my;
244 
245  mapToWorld(x_, y_, mx, my);
246  *min_x = std::min(mx, *min_x);
247  *min_y = std::min(my, *min_y);
248 
249  mapToWorld(x_ + width_, y_ + height_, mx, my);
250  *max_x = std::max(mx, *max_x);
251  *max_y = std::max(my, *max_y);
252 
253  has_updated_data_ = false;
254 }
255 
256 void StaticLayer::updateCosts(costmap_2d::Costmap2D& master_grid, int min_i, int min_j, int max_i, int max_j)
257 {
258  if (!map_received_)
259  return;
260  if (!use_maximum_)
261  updateWithTrueOverwrite(master_grid, min_i, min_j, max_i, max_j);
262  else
263  updateWithMax(master_grid, min_i, min_j, max_i, max_j);
264 }
265 
266 } // namespace rtabmap_ros
#define NULL
virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
LayeredCostmap * layered_costmap_
void reconfigureCB(costmap_2d::GenericPluginConfig &config, uint32_t level)
void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y)
GLM_FUNC_DECL genType min(genType const &x, genType const &y)
dynamic_reconfigure::Server< costmap_2d::GenericPluginConfig > * dsrv_
Definition: static_layer.h:95
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y, bool size_locked=false)
unsigned int size_y_
std::string getGlobalFrameID() const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void incomingUpdate(const map_msgs::OccupancyGridUpdateConstPtr &update)
GLM_FUNC_DECL detail::tmat4x4< T, P > scale(detail::tmat4x4< T, P > const &m, detail::tvec3< T, P > const &v)
ros::Subscriber map_update_sub_
Definition: static_layer.h:90
unsigned int size_x_
void useExtraBounds(double *min_x, double *min_y, double *max_x, double *max_y)
std::string name_
unsigned char unknown_cost_value_
Definition: static_layer.h:92
void incomingMap(const nav_msgs::OccupancyGridConstPtr &new_map)
Callback to update the costmap&#39;s map from the map_server.
#define ROS_INFO(...)
unsigned char interpretValue(unsigned char value)
std::string global_frame_
The global frame for the costmap.
Definition: static_layer.h:82
void updateWithTrueOverwrite(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
unsigned int getSizeInCellsY() const
virtual void updateCosts(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
bool sleep()
detail::uint32 uint32_t
unsigned int getSizeInCellsX() const
GLM_FUNC_DECL genType max(genType const &x, genType const &y)
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
bool ok() const
void updateWithMax(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
virtual void onInitialize()
double getResolution() const
void updateMap(double robot_x, double robot_y, double robot_yaw)
unsigned char * costmap_
ROSCPP_DECL void spinOnce()
r
unsigned char lethal_threshold_
Definition: static_layer.h:92
ros::Subscriber map_sub_
Definition: static_layer.h:90
#define ROS_DEBUG(...)


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Fri Jun 7 2019 21:55:04