hector_elevation_mapping.cpp
Go to the documentation of this file.
2 #include <nodelet/nodelet.h>
4 
5 // compute linear index for given map coords
6 #define MAP_IDX(sx, i, j) ((sx) * (j) + (i))
7 
9 {
11 
12 void ElevationMapping::onInit()
13 {
14  int width, height, zero_elevation;
15 
16  nPrivateHandle = getPrivateNodeHandle();
17  nHandle = getNodeHandle();
18 
19  nPrivateHandle.param("elevation_resolution", elevation_map_meta.resolution_z, 0.01); //[m]
20  nPrivateHandle.param("elevation_zero_level", zero_elevation, 16384); //[cell]
21  elevation_map_meta.zero_elevation = zero_elevation;
22  nPrivateHandle.param("min_observable_elevation", elevation_map_meta.min_elevation, -1.00); //[m]
23  nPrivateHandle.param("max_observable_elevation", elevation_map_meta.max_elevation, 0.30); //[m]
24  nPrivateHandle.param("max_observable_distance", max_observable_distance, 4.00); //[m]
25 
26  nPrivateHandle.param("map_resolution", elevation_map_meta.resolution_xy, 0.05); //[m]
27  nPrivateHandle.param("max_grid_size_x", width, 1024); //[cell]
28  elevation_map_meta.width = width;
29  nPrivateHandle.param("max_grid_size_y", height, 1024); //[cell]
30  elevation_map_meta.height = height;
31 
32  nPrivateHandle.param("publish_poseupdate", publish_poseupdate, true); //[]
33 
34  nPrivateHandle.param("sensor_variance", sensor_variance, 0.001); //[m^2]
35 
36  nPrivateHandle.param("origin_x",elevation_map_meta.origin.position.x, -(double)elevation_map_meta.width*(double)elevation_map_meta.resolution_xy/2.0f); //[m]
37  nPrivateHandle.param("origin_y",elevation_map_meta.origin.position.y, -(double)elevation_map_meta.height*(double)elevation_map_meta.resolution_xy/2.0f); //[m]
38  nPrivateHandle.param("origin_z",elevation_map_meta.origin.position.z, 0.0); //[m]
39  nPrivateHandle.param("orientation_x",elevation_map_meta.origin.orientation.x, 0.0); //[]
40  nPrivateHandle.param("orientation_y",elevation_map_meta.origin.orientation.y, 0.0); //[]
41  nPrivateHandle.param("orientation_z",elevation_map_meta.origin.orientation.z, 0.0); //[]
42  nPrivateHandle.param("orientation_w",elevation_map_meta.origin.orientation.w, 1.0); //[]
43 
44  local_elevation_map.info = elevation_map_meta;
45  global_elevation_map.info = elevation_map_meta;
46 
47  map_meta.origin.position.x = elevation_map_meta.origin.position.x;
48  map_meta.origin.position.y = elevation_map_meta.origin.position.y;
49  map_meta.origin.position.z = elevation_map_meta.origin.position.z;
50 
51  map_meta.origin.orientation.x = elevation_map_meta.origin.orientation.x;
52  map_meta.origin.orientation.y = elevation_map_meta.origin.orientation.y;
53  map_meta.origin.orientation.z = elevation_map_meta.origin.orientation.z;
54  map_meta.origin.orientation.w = elevation_map_meta.origin.orientation.w;
55 
56  map_meta.resolution = elevation_map_meta.resolution_xy;
57  world_map_transform.setTransforms(map_meta);
58 
59  nPrivateHandle.param("map_frame_id", map_frame_id,std::string("map"));
60  nPrivateHandle.param("local_map_frame_id", local_map_frame_id,std::string("base_stabilized"));
61  nPrivateHandle.param("local_elevation_map_topic", local_elevation_map_topic, std::string("elevation_map_local"));
62  nPrivateHandle.param("global_elevation_map_topic", global_elevation_map_topic, std::string("elevation_map_global"));
63  nPrivateHandle.param("point_cloud_topic", point_cloud_topic, std::string("openni/depth/points"));
64  nPrivateHandle.param("grid_map_topic", grid_map_topic, std::string("scanmatcher_map"));
65  nPrivateHandle.param("pose_update_topic",pose_update_topic,std::string("poseupdate"));
66 
67  nPrivateHandle.param("sys_msg_topic", sys_msg_topic, std::string("syscommand"));
68 
69  nPrivateHandle.param("poseupdate_pub_period",poseupdate_pub_period,1.0); //[s]
70  nPrivateHandle.param("poseupdate_height_covariance",poseupdate_height_covariance,0.25); //[m²]
71  nPrivateHandle.param("poseupdate_used_pattern_size",poseupdate_used_pattern_size,3); //[]
72 
73  // allocate memory and set default values
74  local_elevation_map.data = std::vector<int16_t>(elevation_map_meta.width * elevation_map_meta.height,(int16_t)-elevation_map_meta.zero_elevation);
75  global_elevation_map.data = std::vector<int16_t>(elevation_map_meta.width * elevation_map_meta.height,(int16_t)-elevation_map_meta.zero_elevation);
76  cell_variance = std::vector<double>(elevation_map_meta.width * elevation_map_meta.height,std::numeric_limits<double>::max());
77 
78  sub_pointCloud = nHandle.subscribe(point_cloud_topic,1,&ElevationMapping::cloudCallback,this);
79  sub_sysMessage = nHandle.subscribe(sys_msg_topic, 10, &ElevationMapping::sysMessageCallback, this);
80  sub_grid_map_info = nHandle.subscribe(grid_map_topic + "_metadata",1,&ElevationMapping::updateParamsCallback,this);
81 
82  pub_local_map = nPrivateHandle.advertise<hector_elevation_msgs::ElevationGrid>(local_elevation_map_topic, 1, true);
83  pub_local_map_meta = nPrivateHandle.advertise<hector_elevation_msgs::ElevationMapMetaData>(local_elevation_map_topic + "_metadata", 1, true);
84  pub_global_map = nPrivateHandle.advertise<hector_elevation_msgs::ElevationGrid>(global_elevation_map_topic, 1, true);
85  pub_global_map_meta = nPrivateHandle.advertise<hector_elevation_msgs::ElevationMapMetaData>(global_elevation_map_topic + "_metadata", 1, true);
86 
87  pub_local_map_meta.publish(local_elevation_map.info);
88  pub_global_map_meta.publish(global_elevation_map.info);
89 
90  pub_height_update = nPrivateHandle.advertise<geometry_msgs::PoseWithCovarianceStamped>(pose_update_topic, 1, true);
91 
92  if(publish_poseupdate)
93  timer = nHandle.createTimer(ros::Duration(poseupdate_pub_period), &ElevationMapping::timerCallback,this);
94 
95  ROS_INFO("HectorEM: is up and running.");
96 }
97 
99 {
100  ROS_INFO("HectorEM: Shutting down!");
101 }
102 
104 {
105  tf::StampedTransform local_map_transform;
106 
107  // get local map transform
108  try
109  {
112  }
113  catch (tf::TransformException ex)
114  {
115  ROS_DEBUG("HectorEM: localmap transform in timer callback failed");
116  ROS_ERROR("%s",ex.what());
117  return;
118  }
119 
120  // allign grid points
121  Eigen::Vector2f index_world(local_map_transform.getOrigin().x(), local_map_transform.getOrigin().y());
122  Eigen::Vector2f index_map = world_map_transform.getC2Coords(index_world);
123 
124  // check if elevation of current robot position is known, otherwise cancel pose update
125  if(global_elevation_map.data[MAP_IDX(elevation_map_meta.width, (int)index_map(0), (int)index_map(1))] != (int16_t)-elevation_map_meta.zero_elevation)
126  {
127  geometry_msgs::PoseWithCovarianceStamped cell_height_average;
128 
129  int error_level = 0;
130  int pattern_cell_quantity = 4*poseupdate_used_pattern_size*poseupdate_used_pattern_size;
131 
133  // include neighbours
134  for(int x=index_map(0)-poseupdate_used_pattern_size;x<index_map(0)+poseupdate_used_pattern_size;x++)
135  {
136  for(int y=index_map(1)-poseupdate_used_pattern_size;y<index_map(1)+poseupdate_used_pattern_size;y++)
137  {
138  int cell_index = MAP_IDX(elevation_map_meta.width, x, y);
139 
140  if(global_elevation_map.data[cell_index] == (int16_t)-elevation_map_meta.zero_elevation)
141  {
142  // unknown cell
143  error_level++;
144  }
145  else
146  {
147  // cell is knwon, accumulate cell hight
148  cell_height_average.pose.pose.position.z += (global_elevation_map.data[cell_index]-elevation_map_meta.zero_elevation)*elevation_map_meta.resolution_z;
149  }
150  }
151  }
152 
153  // only publish pose update, if more than 1/2 of pattern cells are known
154  if(error_level < pattern_cell_quantity/2)
155  {
156  pattern_cell_quantity -= error_level;
157 
158  cell_height_average.pose.pose.position.z = cell_height_average.pose.pose.position.z/(double)pattern_cell_quantity;
159 
160  cell_height_average.header.frame_id = map_frame_id;
161  cell_height_average.header.stamp = ros::Time::now();
162 
163  cell_height_average.pose.covariance.at(0) = 0.0; //no x-position information
164  cell_height_average.pose.covariance.at(7) = 0.0; //no y-position information
165  cell_height_average.pose.covariance.at(14) = 1.0/poseupdate_height_covariance;
166 
167  pub_height_update.publish(cell_height_average);
168 
169  ROS_DEBUG("HectorEM: published height update %f",cell_height_average.pose.pose.position.z);
170 
171  }
172  }
173 }
174 
175 void ElevationMapping::sysMessageCallback(const std_msgs::String& string)
176 {
177  ROS_DEBUG("HectorEM: sysMsgCallback, msg contents: %s", string.data.c_str());
178 
179  if (string.data == "reset")
180  {
181  ROS_INFO("HectorEM: reset");
182 
183  // allocate memory and set default values
184  local_elevation_map.data = std::vector<int16_t>(elevation_map_meta.width * elevation_map_meta.height,(int16_t)-elevation_map_meta.zero_elevation);
185  global_elevation_map.data = std::vector<int16_t>(elevation_map_meta.width * elevation_map_meta.height,(int16_t)-elevation_map_meta.zero_elevation);
186  cell_variance = std::vector<double>(elevation_map_meta.width * elevation_map_meta.height,std::numeric_limits<double>::max());
187 
188  }
189 }
190 
191 void ElevationMapping::updateParamsCallback(const nav_msgs::MapMetaData& map_meta_data)
192 {
193  ROS_DEBUG("HectorEM: received new grid map meta data -> overwrite old parameters");
194 
195  // set new parameters
196  elevation_map_meta.width = map_meta_data.width;
197  elevation_map_meta.height = map_meta_data.height;
198  elevation_map_meta.resolution_xy = map_meta_data.resolution;
199 
200  elevation_map_meta.origin.position.x = map_meta_data.origin.position.x;
201  elevation_map_meta.origin.position.y = map_meta_data.origin.position.y;
202  elevation_map_meta.origin.position.z = map_meta_data.origin.position.z;
203 
204  elevation_map_meta.origin.orientation.x = map_meta_data.origin.orientation.x;
205  elevation_map_meta.origin.orientation.y = map_meta_data.origin.orientation.y;
206  elevation_map_meta.origin.orientation.z = map_meta_data.origin.orientation.z;
207  elevation_map_meta.origin.orientation.w = map_meta_data.origin.orientation.w;
208 
211 
212  map_meta = map_meta_data;
213  world_map_transform.setTransforms(map_meta);
214 
215  // allocate memory and set default values
216  local_elevation_map.data = std::vector<int16_t>(elevation_map_meta.width * elevation_map_meta.height,(int16_t)-elevation_map_meta.zero_elevation);
217  global_elevation_map.data = std::vector<int16_t>(elevation_map_meta.width * elevation_map_meta.height,(int16_t)-elevation_map_meta.zero_elevation);
218  cell_variance = std::vector<double>(elevation_map_meta.width * elevation_map_meta.height,std::numeric_limits<double>::max());
219 
222 }
223 
224 void ElevationMapping::cloudCallback(const sensor_msgs::PointCloud2ConstPtr& pointcloud2_sensor_msg)
225 {
226  pcl::PointCloud<pcl::PointXYZ>::Ptr pointcloud2_map_pcl (new pcl::PointCloud<pcl::PointXYZ> ()),
227  pointcloud2_sensor_pcl (new pcl::PointCloud<pcl::PointXYZ> ());
228  tf::StampedTransform local_map_transform;
229 
230  ROS_DEBUG("HectorEM received a point cloud.");
231 
232  // converting PointCloud2 msg format to pcl pointcloud format in order to read the 3d data
233  pcl::fromROSMsg(*pointcloud2_sensor_msg, *pointcloud2_sensor_pcl);
234 
235 
236  // transform cloud to /map frame
237  try
238  {
239  listener.waitForTransform(map_frame_id, pointcloud2_sensor_msg->header.frame_id,pointcloud2_sensor_msg->header.stamp,ros::Duration(1.0));
240  pcl_ros::transformPointCloud(map_frame_id,*pointcloud2_sensor_pcl,*pointcloud2_map_pcl,listener);
241  }
242  catch (tf::TransformException ex)
243  {
244  ROS_ERROR("%s",ex.what());
245  ROS_DEBUG("HectorEM: pointcloud transform failed");
246  return;
247  }
248 
249  // get local map transform
250  try
251  {
252  listener.waitForTransform(map_frame_id, local_map_frame_id,pointcloud2_sensor_msg->header.stamp,ros::Duration(1.0));
253  listener.lookupTransform(map_frame_id, local_map_frame_id, pointcloud2_sensor_msg->header.stamp, local_map_transform);
254  }
255  catch (tf::TransformException ex)
256  {
257  ROS_ERROR("%s",ex.what());
258  ROS_DEBUG("HectorEM: localmap transform in cloud callback failed");
259  return;
260  }
261 
262  bool local_map_is_subscribed = (pub_local_map.getNumSubscribers () > 0);
263  bool global_map_is_subscribed = (pub_global_map.getNumSubscribers () > 0);
264 
265  if(local_map_is_subscribed)
266  local_elevation_map.data = std::vector<int16_t>(elevation_map_meta.width * elevation_map_meta.height,(int16_t)-elevation_map_meta.zero_elevation);
267 
268  unsigned int size = (unsigned int)pointcloud2_map_pcl->points.size();
269 
270  // iterate trough all points
271  for (unsigned int k = 0; k < size; ++k)
272  {
273  const pcl::PointXYZ& pt_cloud = pointcloud2_map_pcl->points[k];
274 
275  double measurement_distance = pointcloud2_sensor_pcl->points[k].z;
276 
277  // check for invalid measurements
278  if (isnan(pt_cloud.x) || isnan(pt_cloud.y) || isnan(pt_cloud.z))
279  continue;
280 
281  // check max distance (manhatten norm)
282  if(max_observable_distance < measurement_distance)
283  continue;
284 
285  // check min/max height
286  if(elevation_map_meta.min_elevation+local_map_transform.getOrigin().z() > pt_cloud.z || elevation_map_meta.max_elevation+local_map_transform.getOrigin().z() < pt_cloud.z)
287  continue;
288 
289  // allign grid points
290  Eigen::Vector2f index_world(pt_cloud.x, pt_cloud.y);
291  Eigen::Vector2f index_map (world_map_transform.getC2Coords(index_world));
292 
293  unsigned int cell_index = MAP_IDX(elevation_map_meta.width, (int)round(index_map(0)), (int)round(index_map(1)));
294 
295  int16_t* pt_local_map = &local_elevation_map.data[cell_index];
296  int16_t* pt_global_map = &global_elevation_map.data[cell_index];
297  double* pt_var = &cell_variance[cell_index];
298 
299 
300  if(local_map_is_subscribed)
301  {
302  // elevation in current cell in meter
303  double cell_elevation = elevation_map_meta.resolution_z*(*pt_local_map-elevation_map_meta.zero_elevation);
304 
305  // store maximum of each cell
306  if(pt_cloud.z > cell_elevation)
307  *pt_local_map = (int16_t)(round(pt_cloud.z/elevation_map_meta.resolution_z) + (int16_t)elevation_map_meta.zero_elevation);
308 
309  // filter each cell localy
310 // double measurement_variance = sensor_variance*(measurement_distance*measurement_distance);
311 // if(*pt_local_map == (int16_t)-elevation_map_meta.zero_elevation)
312 // {
313 // // unknown cell -> use current measurement
314 // *pt_local_map = (int16_t)(round(pt_cloud.z/elevation_map_meta.resolution_z) + (int16_t)elevation_map_meta.zero_elevation);
315 // *pt_var = measurement_variance;
316 // }
317 // else
318 // {
319 // // fuse cell_elevation with measurement
320 // *pt_local_map = (int16_t) (round(((measurement_variance * cell_elevation + *pt_var * pt_cloud.z)/(*pt_var + measurement_variance))/elevation_map_meta.resolution_z) + (int16_t)elevation_map_meta.zero_elevation);
321 // *pt_var = (measurement_variance * *pt_var)/(measurement_variance + *pt_var);
322 // }
323  }
324 
325  if(publish_poseupdate || global_map_is_subscribed)
326  {
327  // fuse new measurements with existing map
328 
329  // elevation in current cell in meter
330  double cell_elevation = elevation_map_meta.resolution_z*(*pt_global_map-elevation_map_meta.zero_elevation);
331 
332  // measurement variance
333  double measurement_variance = sensor_variance*(measurement_distance*measurement_distance);
334 
335  // mahalanobis distance
336  double mahalanobis_distance = sqrt((pt_cloud.z - cell_elevation)*(pt_cloud.z - cell_elevation)/(measurement_variance*measurement_variance));
337 
338  if(pt_cloud.z > cell_elevation && (mahalanobis_distance > 5.0))
339  {
340  *pt_global_map = (int16_t)(round(pt_cloud.z/elevation_map_meta.resolution_z) + (int16_t)elevation_map_meta.zero_elevation);
341  *pt_var = measurement_variance;
342  continue;
343  }
344 
345  if((pt_cloud.z < cell_elevation) && (mahalanobis_distance > 5.0))
346  {
347  *pt_global_map = (int16_t) (round(((measurement_variance * cell_elevation + *pt_var * pt_cloud.z)/(*pt_var + measurement_variance))/elevation_map_meta.resolution_z) + (int16_t)elevation_map_meta.zero_elevation);
348  //*pt_var = (measurement_variance * *pt_var)/(measurement_variance + *pt_var);
349  *pt_var = measurement_variance;
350  continue;
351  }
352 
353  *pt_global_map = (int16_t) (round(((measurement_variance * cell_elevation + *pt_var * pt_cloud.z)/(*pt_var + measurement_variance))/elevation_map_meta.resolution_z) + (int16_t)elevation_map_meta.zero_elevation);
354  *pt_var = (measurement_variance * *pt_var)/(measurement_variance + *pt_var);
355  }
356  }
357 
358 
359  if(local_map_is_subscribed)
360  {
361  // set the header information on the map
362  local_elevation_map.header.stamp = pointcloud2_sensor_msg->header.stamp;
363  local_elevation_map.header.frame_id = map_frame_id;
364 
366  }
367 
368  if(global_map_is_subscribed)
369  {
370  // set the header information on the map
371  global_elevation_map.header.stamp = pointcloud2_sensor_msg->header.stamp;
372  global_elevation_map.header.frame_id = map_frame_id;
373 
375  }
376 
377 }
378 
379 }
void publish(const boost::shared_ptr< M > &message) const
#define MAP_IDX(sx, i, j)
PLUGINLIB_EXPORT_CLASS(BAGReader, nodelet::Nodelet)
hector_elevation_msgs::ElevationGrid global_elevation_map
void updateParamsCallback(const nav_msgs::MapMetaData &map_meta_data)
updateMapParamsCallback updates the map meta information if someone has changed it ...
HectorMapTools::CoordinateTransformer< float > world_map_transform
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
hector_elevation_msgs::ElevationGrid local_elevation_map
TFSIMD_FORCE_INLINE const tfScalar & y() const
void timerCallback(const ros::TimerEvent &event)
timerCallback publishes periodically a height pose update
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
TFSIMD_FORCE_INLINE const tfScalar & x() const
TFSIMD_FORCE_INLINE const tfScalar & z() const
void sysMessageCallback(const std_msgs::String &string)
sysMessageCallback This function listen to system messages
#define ROS_INFO(...)
TFSIMD_FORCE_INLINE const tfScalar & y() const
TFSIMD_FORCE_INLINE const tfScalar & x() const
void cloudCallback(const sensor_msgs::PointCloud2ConstPtr &pointcloud2_sensor_msg)
cloudCallback get called if a new 3D point cloud is avaible
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
uint32_t getNumSubscribers() const
void transformPointCloud(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const tf::Transform &transform)
static Time now()
hector_elevation_msgs::ElevationMapMetaData elevation_map_meta
#define ROS_ERROR(...)
#define ROS_DEBUG(...)


hector_elevation_mapping
Author(s):
autogenerated on Mon Jun 10 2019 13:34:35