HectorMappingRos.cpp
Go to the documentation of this file.
1 //=================================================================================================
2 // Copyright (c) 2011, Stefan Kohlbrecher, TU Darmstadt
3 // All rights reserved.
4 
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 // * Redistributions of source code must retain the above copyright
8 // notice, this list of conditions and the following disclaimer.
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 // * Neither the name of the Simulation, Systems Optimization and Robotics
13 // group, TU Darmstadt nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without
15 // specific prior written permission.
16 
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
18 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
19 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //=================================================================================================
28 
29 #include "HectorMappingRos.h"
30 
31 #include "map/GridMap.h"
32 
33 #include <geometry_msgs/PoseWithCovarianceStamped.h>
34 #include <nav_msgs/Odometry.h>
35 
36 #include "sensor_msgs/PointCloud2.h"
37 
38 #include "HectorDrawings.h"
40 #include "HectorMapMutex.h"
41 
42 #ifndef TF_SCALAR_H
43  typedef btScalar tfScalar;
44 #endif
45 
47  : debugInfoProvider(0)
48  , hectorDrawings(0)
49  , lastGetMapUpdateIndex(-100)
50  , tfB_(0)
51  , map__publish_thread_(0)
52  , initial_pose_set_(false)
53 {
54  ros::NodeHandle private_nh_("~");
55 
56  std::string mapTopic_ = "map";
57 
58  private_nh_.param("pub_drawings", p_pub_drawings, false);
59  private_nh_.param("pub_debug_output", p_pub_debug_output_, false);
60  private_nh_.param("pub_map_odom_transform", p_pub_map_odom_transform_,true);
61  private_nh_.param("pub_odometry", p_pub_odometry_,false);
62  private_nh_.param("advertise_map_service", p_advertise_map_service_,true);
63  private_nh_.param("scan_subscriber_queue_size", p_scan_subscriber_queue_size_, 5);
64 
65  private_nh_.param("map_resolution", p_map_resolution_, 0.025);
66  private_nh_.param("map_size", p_map_size_, 1024);
67  private_nh_.param("map_start_x", p_map_start_x_, 0.5);
68  private_nh_.param("map_start_y", p_map_start_y_, 0.5);
69  private_nh_.param("map_multi_res_levels", p_map_multi_res_levels_, 3);
70 
71  private_nh_.param("update_factor_free", p_update_factor_free_, 0.4);
72  private_nh_.param("update_factor_occupied", p_update_factor_occupied_, 0.9);
73 
74  private_nh_.param("map_update_distance_thresh", p_map_update_distance_threshold_, 0.4);
75  private_nh_.param("map_update_angle_thresh", p_map_update_angle_threshold_, 0.9);
76 
77  private_nh_.param("scan_topic", p_scan_topic_, std::string("scan"));
78  private_nh_.param("sys_msg_topic", p_sys_msg_topic_, std::string("syscommand"));
79  private_nh_.param("pose_update_topic", p_pose_update_topic_, std::string("poseupdate"));
80 
81  private_nh_.param("use_tf_scan_transformation", p_use_tf_scan_transformation_,true);
82  private_nh_.param("use_tf_pose_start_estimate", p_use_tf_pose_start_estimate_,false);
83  private_nh_.param("map_with_known_poses", p_map_with_known_poses_, false);
84 
85  private_nh_.param("base_frame", p_base_frame_, std::string("base_link"));
86  private_nh_.param("map_frame", p_map_frame_, std::string("map"));
87  private_nh_.param("odom_frame", p_odom_frame_, std::string("odom"));
88 
89  private_nh_.param("pub_map_scanmatch_transform", p_pub_map_scanmatch_transform_,true);
90  private_nh_.param("tf_map_scanmatch_transform_frame_name", p_tf_map_scanmatch_transform_frame_name_, std::string("scanmatcher_frame"));
91 
92  private_nh_.param("output_timing", p_timing_output_,false);
93 
94  private_nh_.param("map_pub_period", p_map_pub_period_, 2.0);
95 
96  double tmp = 0.0;
97  private_nh_.param("laser_min_dist", tmp, 0.4);
98  p_sqr_laser_min_dist_ = static_cast<float>(tmp*tmp);
99 
100  private_nh_.param("laser_max_dist", tmp, 30.0);
101  p_sqr_laser_max_dist_ = static_cast<float>(tmp*tmp);
102 
103  private_nh_.param("laser_z_min_value", tmp, -1.0);
104  p_laser_z_min_value_ = static_cast<float>(tmp);
105 
106  private_nh_.param("laser_z_max_value", tmp, 1.0);
107  p_laser_z_max_value_ = static_cast<float>(tmp);
108 
109  if (p_pub_drawings)
110  {
111  ROS_INFO("HectorSM publishing debug drawings");
113  }
114 
116  {
117  ROS_INFO("HectorSM publishing debug info");
119  }
120 
121  if(p_pub_odometry_)
122  {
123  odometryPublisher_ = node_.advertise<nav_msgs::Odometry>("scanmatch_odom", 50);
124  }
125 
127  slamProcessor->setUpdateFactorFree(p_update_factor_free_);
128  slamProcessor->setUpdateFactorOccupied(p_update_factor_occupied_);
129  slamProcessor->setMapUpdateMinDistDiff(p_map_update_distance_threshold_);
130  slamProcessor->setMapUpdateMinAngleDiff(p_map_update_angle_threshold_);
131 
132  int mapLevels = slamProcessor->getMapLevels();
133  mapLevels = 1;
134 
135  for (int i = 0; i < mapLevels; ++i)
136  {
138  slamProcessor->addMapMutex(i, new HectorMapMutex());
139 
140  std::string mapTopicStr(mapTopic_);
141 
142  if (i != 0)
143  {
144  mapTopicStr.append("_" + boost::lexical_cast<std::string>(i));
145  }
146 
147  std::string mapMetaTopicStr(mapTopicStr);
148  mapMetaTopicStr.append("_metadata");
149 
151  tmp.mapPublisher_ = node_.advertise<nav_msgs::OccupancyGrid>(mapTopicStr, 1, true);
152  tmp.mapMetadataPublisher_ = node_.advertise<nav_msgs::MapMetaData>(mapMetaTopicStr, 1, true);
153 
154  if ( (i == 0) && p_advertise_map_service_)
155  {
157  }
158 
159  setServiceGetMapData(tmp.map_, slamProcessor->getGridMap(i));
160 
161  if ( i== 0){
162  mapPubContainer[i].mapMetadataPublisher_.publish(mapPubContainer[i].map_.map.info);
163  }
164  }
165 
166  ROS_INFO("HectorSM p_base_frame_: %s", p_base_frame_.c_str());
167  ROS_INFO("HectorSM p_map_frame_: %s", p_map_frame_.c_str());
168  ROS_INFO("HectorSM p_odom_frame_: %s", p_odom_frame_.c_str());
169  ROS_INFO("HectorSM p_scan_topic_: %s", p_scan_topic_.c_str());
170  ROS_INFO("HectorSM p_use_tf_scan_transformation_: %s", p_use_tf_scan_transformation_ ? ("true") : ("false"));
171  ROS_INFO("HectorSM p_pub_map_odom_transform_: %s", p_pub_map_odom_transform_ ? ("true") : ("false"));
172  ROS_INFO("HectorSM p_scan_subscriber_queue_size_: %d", p_scan_subscriber_queue_size_);
173  ROS_INFO("HectorSM p_map_pub_period_: %f", p_map_pub_period_);
174  ROS_INFO("HectorSM p_update_factor_free_: %f", p_update_factor_free_);
175  ROS_INFO("HectorSM p_update_factor_occupied_: %f", p_update_factor_occupied_);
176  ROS_INFO("HectorSM p_map_update_distance_threshold_: %f ", p_map_update_distance_threshold_);
177  ROS_INFO("HectorSM p_map_update_angle_threshold_: %f", p_map_update_angle_threshold_);
178  ROS_INFO("HectorSM p_laser_z_min_value_: %f", p_laser_z_min_value_);
179  ROS_INFO("HectorSM p_laser_z_max_value_: %f", p_laser_z_max_value_);
180 
183 
184  poseUpdatePublisher_ = node_.advertise<geometry_msgs::PoseWithCovarianceStamped>(p_pose_update_topic_, 1, false);
185  posePublisher_ = node_.advertise<geometry_msgs::PoseStamped>("slam_out_pose", 1, false);
186 
187  scan_point_cloud_publisher_ = node_.advertise<sensor_msgs::PointCloud>("slam_cloud",1,false);
188 
190  ROS_ASSERT(tfB_);
191 
192  /*
193  bool p_use_static_map_ = false;
194 
195  if (p_use_static_map_){
196  mapSubscriber_ = node_.subscribe(mapTopic_, 1, &HectorMappingRos::staticMapCallback, this);
197  }
198  */
199 
202  initial_pose_filter_->registerCallback(boost::bind(&HectorMappingRos::initialPoseCallback, this, _1));
203 
204 
205  map__publish_thread_ = new boost::thread(boost::bind(&HectorMappingRos::publishMapLoop, this, p_map_pub_period_));
206 
208 
210 }
211 
213 {
214  delete slamProcessor;
215 
216  if (hectorDrawings)
217  delete hectorDrawings;
218 
219  if (debugInfoProvider)
220  delete debugInfoProvider;
221 
222  if (tfB_)
223  delete tfB_;
224 
226  delete map__publish_thread_;
227 }
228 
229 void HectorMappingRos::scanCallback(const sensor_msgs::LaserScan& scan)
230 {
231  if (hectorDrawings)
232  {
233  hectorDrawings->setTime(scan.header.stamp);
234  }
235 
236  ros::WallTime startTime = ros::WallTime::now();
237 
239  {
241  {
243  }
244  }
245  else
246  {
247  ros::Duration dur (0.5);
248 
249  if (tf_.waitForTransform(p_base_frame_,scan.header.frame_id, scan.header.stamp,dur))
250  {
251  tf::StampedTransform laserTransform;
252  tf_.lookupTransform(p_base_frame_,scan.header.frame_id, scan.header.stamp, laserTransform);
253 
254  //projector_.transformLaserScanToPointCloud(p_base_frame_ ,scan, pointCloud,tf_);
256 
259  }
260 
261  Eigen::Vector3f startEstimate(Eigen::Vector3f::Zero());
262 
264  {
265  if (initial_pose_set_){
266  initial_pose_set_ = false;
267  startEstimate = initial_pose_;
269 
270  try
271  {
272  tf::StampedTransform stamped_pose;
273 
274  tf_.waitForTransform(p_map_frame_,p_base_frame_, scan.header.stamp, ros::Duration(0.5));
275  tf_.lookupTransform(p_map_frame_, p_base_frame_, scan.header.stamp, stamped_pose);
276 
277  tfScalar yaw, pitch, roll;
278  stamped_pose.getBasis().getEulerYPR(yaw, pitch, roll);
279 
280  startEstimate = Eigen::Vector3f(stamped_pose.getOrigin().getX(),stamped_pose.getOrigin().getY(), yaw);
281  }
282  catch(tf::TransformException e)
283  {
284  ROS_ERROR("Transform from %s to %s failed\n", p_map_frame_.c_str(), p_base_frame_.c_str());
285  startEstimate = slamProcessor->getLastScanMatchPose();
286  }
287 
288  }else{
289  startEstimate = slamProcessor->getLastScanMatchPose();
290  }
291 
292 
294  slamProcessor->update(laserScanContainer, startEstimate, true);
295  }else{
296  slamProcessor->update(laserScanContainer, startEstimate);
297  }
298  }
299 
300  }else{
301  ROS_INFO("lookupTransform %s to %s timed out. Could not transform laser scan into base_frame.", p_base_frame_.c_str(), scan.header.frame_id.c_str());
302  return;
303  }
304  }
305 
306  if (p_timing_output_)
307  {
308  ros::WallDuration duration = ros::WallTime::now() - startTime;
309  ROS_INFO("HectorSLAM Iter took: %f milliseconds", duration.toSec()*1000.0f );
310  }
311 
312  //If we're just building a map with known poses, we're finished now. Code below this point publishes the localization results.
314  {
315  return;
316  }
317 
319 
322 
323  if(p_pub_odometry_)
324  {
325  nav_msgs::Odometry tmp;
327 
328  tmp.header = poseInfoContainer_.getPoseWithCovarianceStamped().header;
329  tmp.child_frame_id = p_base_frame_;
331  }
332 
334  {
335  tf::StampedTransform odom_to_base;
336 
337  try
338  {
339  tf_.waitForTransform(p_odom_frame_, p_base_frame_, scan.header.stamp, ros::Duration(0.5));
340  tf_.lookupTransform(p_odom_frame_, p_base_frame_, scan.header.stamp, odom_to_base);
341  }
342  catch(tf::TransformException e)
343  {
344  ROS_ERROR("Transform failed during publishing of map_odom transform: %s",e.what());
345  odom_to_base.setIdentity();
346  }
349  }
350 
353  }
354 }
355 
356 void HectorMappingRos::sysMsgCallback(const std_msgs::String& string)
357 {
358  ROS_INFO("HectorSM sysMsgCallback, msg contents: %s", string.data.c_str());
359 
360  if (string.data == "reset")
361  {
362  ROS_INFO("HectorSM reset");
363  slamProcessor->reset();
364  }
365 }
366 
367 bool HectorMappingRos::mapCallback(nav_msgs::GetMap::Request &req,
368  nav_msgs::GetMap::Response &res)
369 {
370  ROS_INFO("HectorSM Map service called");
371  res = mapPubContainer[0].map_;
372  return true;
373 }
374 
376 {
377  nav_msgs::GetMap::Response& map_ (mapPublisher.map_);
378 
379  //only update map if it changed
380  if (lastGetMapUpdateIndex != gridMap.getUpdateIndex())
381  {
382 
383  int sizeX = gridMap.getSizeX();
384  int sizeY = gridMap.getSizeY();
385 
386  int size = sizeX * sizeY;
387 
388  std::vector<int8_t>& data = map_.map.data;
389 
390  //std::vector contents are guaranteed to be contiguous, use memset to set all to unknown to save time in loop
391  memset(&data[0], -1, sizeof(int8_t) * size);
392 
393  if (mapMutex)
394  {
395  mapMutex->lockMap();
396  }
397 
398  for(int i=0; i < size; ++i)
399  {
400  if(gridMap.isFree(i))
401  {
402  data[i] = 0;
403  }
404  else if (gridMap.isOccupied(i))
405  {
406  data[i] = 100;
407  }
408  }
409 
411 
412  if (mapMutex)
413  {
414  mapMutex->unlockMap();
415  }
416  }
417 
418  map_.map.header.stamp = timestamp;
419 
420  mapPublisher.mapPublisher_.publish(map_.map);
421 }
422 
423 bool HectorMappingRos::rosLaserScanToDataContainer(const sensor_msgs::LaserScan& scan, hectorslam::DataContainer& dataContainer, float scaleToMap)
424 {
425  size_t size = scan.ranges.size();
426 
427  float angle = scan.angle_min;
428 
429  dataContainer.clear();
430 
431  dataContainer.setOrigo(Eigen::Vector2f::Zero());
432 
433  float maxRangeForContainer = scan.range_max - 0.1f;
434 
435  for (size_t i = 0; i < size; ++i)
436  {
437  float dist = scan.ranges[i];
438 
439  if ( (dist > scan.range_min) && (dist < maxRangeForContainer))
440  {
441  dist *= scaleToMap;
442  dataContainer.add(Eigen::Vector2f(cos(angle) * dist, sin(angle) * dist));
443  }
444 
445  angle += scan.angle_increment;
446  }
447 
448  return true;
449 }
450 
451 bool HectorMappingRos::rosPointCloudToDataContainer(const sensor_msgs::PointCloud& pointCloud, const tf::StampedTransform& laserTransform, hectorslam::DataContainer& dataContainer, float scaleToMap)
452 {
453  size_t size = pointCloud.points.size();
454  //ROS_INFO("size: %d", size);
455 
456  dataContainer.clear();
457 
458  tf::Vector3 laserPos (laserTransform.getOrigin());
459  dataContainer.setOrigo(Eigen::Vector2f(laserPos.x(), laserPos.y())*scaleToMap);
460 
461  for (size_t i = 0; i < size; ++i)
462  {
463 
464  const geometry_msgs::Point32& currPoint(pointCloud.points[i]);
465 
466  float dist_sqr = currPoint.x*currPoint.x + currPoint.y* currPoint.y;
467 
468  if ( (dist_sqr > p_sqr_laser_min_dist_) && (dist_sqr < p_sqr_laser_max_dist_) ){
469 
470  if ( (currPoint.x < 0.0f) && (dist_sqr < 0.50f)){
471  continue;
472  }
473 
474  tf::Vector3 pointPosBaseFrame(laserTransform * tf::Vector3(currPoint.x, currPoint.y, currPoint.z));
475 
476  float pointPosLaserFrameZ = pointPosBaseFrame.z() - laserPos.z();
477 
478  if (pointPosLaserFrameZ > p_laser_z_min_value_ && pointPosLaserFrameZ < p_laser_z_max_value_)
479  {
480  dataContainer.add(Eigen::Vector2f(pointPosBaseFrame.x(),pointPosBaseFrame.y())*scaleToMap);
481  }
482  }
483  }
484 
485  return true;
486 }
487 
488 void HectorMappingRos::setServiceGetMapData(nav_msgs::GetMap::Response& map_, const hectorslam::GridMap& gridMap)
489 {
490  Eigen::Vector2f mapOrigin (gridMap.getWorldCoords(Eigen::Vector2f::Zero()));
491  mapOrigin.array() -= gridMap.getCellLength()*0.5f;
492 
493  map_.map.info.origin.position.x = mapOrigin.x();
494  map_.map.info.origin.position.y = mapOrigin.y();
495  map_.map.info.origin.orientation.w = 1.0;
496 
497  map_.map.info.resolution = gridMap.getCellLength();
498 
499  map_.map.info.width = gridMap.getSizeX();
500  map_.map.info.height = gridMap.getSizeY();
501 
502  map_.map.header.frame_id = p_map_frame_;
503  map_.map.data.resize(map_.map.info.width * map_.map.info.height);
504 }
505 
506 /*
507 void HectorMappingRos::setStaticMapData(const nav_msgs::OccupancyGrid& map)
508 {
509  float cell_length = map.info.resolution;
510  Eigen::Vector2f mapOrigin (map.info.origin.position.x + cell_length*0.5f,
511  map.info.origin.position.y + cell_length*0.5f);
512 
513  int map_size_x = map.info.width;
514  int map_size_y = map.info.height;
515 
516  slamProcessor = new hectorslam::HectorSlamProcessor(cell_length, map_size_x, map_size_y, Eigen::Vector2f(0.0f, 0.0f), 1, hectorDrawings, debugInfoProvider);
517 }
518 */
519 
520 
521 void HectorMappingRos::publishMapLoop(double map_pub_period)
522 {
523  ros::Rate r(1.0 / map_pub_period);
524  while(ros::ok())
525  {
526  //ros::WallTime t1 = ros::WallTime::now();
527  ros::Time mapTime (ros::Time::now());
528  //publishMap(mapPubContainer[2],slamProcessor->getGridMap(2), mapTime);
529  //publishMap(mapPubContainer[1],slamProcessor->getGridMap(1), mapTime);
531 
532  //ros::WallDuration t2 = ros::WallTime::now() - t1;
533 
534  //std::cout << "time s: " << t2.toSec();
535  //ROS_INFO("HectorSM ms: %4.2f", t2.toSec()*1000.0f);
536 
537  r.sleep();
538  }
539 }
540 
541 void HectorMappingRos::staticMapCallback(const nav_msgs::OccupancyGrid& map)
542 {
543 
544 }
545 
546 void HectorMappingRos::initialPoseCallback(const geometry_msgs::PoseWithCovarianceStampedConstPtr& msg)
547 {
548  initial_pose_set_ = true;
549 
550  tf::Pose pose;
551  tf::poseMsgToTF(msg->pose.pose, pose);
552  initial_pose_ = Eigen::Vector3f(msg->pose.pose.position.x, msg->pose.pose.position.y, tf::getYaw(pose.getRotation()));
553  ROS_INFO("Setting initial pose with world coords x: %f y: %f yaw: %f", initial_pose_[0], initial_pose_[1], initial_pose_[2]);
554 }
555 
556 
bool rosLaserScanToDataContainer(const sensor_msgs::LaserScan &scan, hectorslam::DataContainer &dataContainer, float scaleToMap)
void projectLaser(const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud &cloud_out, double range_cutoff=-1.0, int channel_options=channel_option::Default)
tf::TransformBroadcaster * tfB_
ros::Publisher odometryPublisher_
bool p_pub_map_scanmatch_transform_
static void poseMsgToTF(const geometry_msgs::Pose &msg, Pose &bt)
tf::MessageFilter< geometry_msgs::PoseWithCovarianceStamped > * initial_pose_filter_
HectorDebugInfoProvider * debugInfoProvider
void publishMap(MapPublisherContainer &map_, const hectorslam::GridMap &gridMap, ros::Time timestamp, MapLockerInterface *mapMutex=0)
void publish(const boost::shared_ptr< M > &message) const
laser_geometry::LaserProjection projector_
void staticMapCallback(const nav_msgs::OccupancyGrid &map)
double tfScalar
const geometry_msgs::PoseStamped & getPoseStamped()
boost::thread * map__publish_thread_
ros::Time lastMapPublishTime
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void getEulerYPR(tfScalar &yaw, tfScalar &pitch, tfScalar &roll, unsigned int solution_number=1) const
std::vector< MapPublisherContainer > mapPubContainer
TFSIMD_FORCE_INLINE Matrix3x3 & getBasis()
static double getYaw(const Quaternion &bt_q)
const geometry_msgs::PoseWithCovarianceStamped & getPoseWithCovarianceStamped()
void update(const Eigen::Vector3f &slamPose, const Eigen::Matrix3f &slamCov, const ros::Time &stamp, const std::string &frame_id)
bool mapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
void setOrigo(const DataPointType &origoIn)
ros::Publisher mapPublisher_
double p_map_update_distance_threshold_
PoseInfoContainer poseInfoContainer_
TFSIMD_FORCE_INLINE const tfScalar & getY() const
std::string p_scan_topic_
ros::Subscriber scanSubscriber_
const tf::Transform & getTfTransform()
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
bool p_use_tf_pose_start_estimate_
nav_msgs::GetMap::Response map_
const Eigen::Vector3f & getLastScanMatchPose() const
MapLockerInterface * getMapMutex(int i)
hectorslam::HectorSlamProcessor * slamProcessor
Eigen::Vector3f initial_pose_
ros::ServiceServer dynamicMapServiceServer_
const Eigen::Matrix3f & getLastScanMatchCovariance() const
void sysMsgCallback(const std_msgs::String &string)
ros::NodeHandle node_
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
HectorDrawings * hectorDrawings
void setIdentity()
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
int getSizeY() const
Definition: GridMapBase.h:62
TFSIMD_FORCE_INLINE const tfScalar & x() const
ros::Publisher scan_point_cloud_publisher_
std::string p_tf_map_scanmatch_transform_frame_name_
sensor_msgs::PointCloud laser_point_cloud_
ros::Subscriber sysMsgSubscriber_
bool isOccupied(int xMap, int yMap) const
ros::Publisher posePublisher_
TFSIMD_FORCE_INLINE const tfScalar & z() const
bool rosPointCloudToDataContainer(const sensor_msgs::PointCloud &pointCloud, const tf::StampedTransform &laserTransform, hectorslam::DataContainer &dataContainer, float scaleToMap)
int getUpdateIndex() const
Definition: GridMapBase.h:329
void scanCallback(const sensor_msgs::LaserScan &scan)
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
double p_map_update_angle_threshold_
virtual void lockMap()=0
std::string p_odom_frame_
ROSCPP_DECL bool ok()
TFSIMD_FORCE_INLINE const tfScalar & y() const
void sendTransform(const StampedTransform &transform)
std::string p_map_frame_
Transform inverse() const
btScalar tfScalar
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::string p_pose_update_topic_
ros::Publisher mapMetadataPublisher_
bool p_use_tf_scan_transformation_
int getSizeX() const
Definition: GridMapBase.h:61
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
Eigen::Vector2f getWorldCoords(const Eigen::Vector2f &mapCoords) const
Definition: GridMapBase.h:210
bool sleep()
float getCellLength() const
Definition: GridMapBase.h:296
double p_update_factor_occupied_
uint32_t getNumSubscribers() const
static WallTime now()
void publishMapLoop(double p_map_pub_period_)
Quaternion getRotation() const
hectorslam::DataContainer laserScanContainer
std::string p_sys_msg_topic_
ros::Publisher poseUpdatePublisher_
const GridMap & getGridMap(int mapLevel=0) const
TFSIMD_FORCE_INLINE const tfScalar & getX() const
static Time now()
void setTime(const ros::Time &time)
bool isFree(int xMap, int yMap) const
void initialPoseCallback(const geometry_msgs::PoseWithCovarianceStampedConstPtr &msg)
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
virtual void unlockMap()=0
#define ROS_ASSERT(cond)
void update(const DataContainer &dataContainer, const Eigen::Vector3f &poseHintWorld, bool map_without_matching=false)
void setServiceGetMapData(nav_msgs::GetMap::Response &map_, const hectorslam::GridMap &gridMap)
void add(const DataPointType &dataPoint)
std::string p_base_frame_
#define ROS_ERROR(...)
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
tf::Transform map_to_odom_
tf::TransformListener tf_
message_filters::Subscriber< geometry_msgs::PoseWithCovarianceStamped > * initial_pose_sub_
Connection registerCallback(const C &callback)


hector_mapping
Author(s): Stefan Kohlbrecher
autogenerated on Sun Nov 3 2019 03:18:33