129 #include "nav_msgs/MapMetaData.h"
136 #include <boost/foreach.hpp>
137 #define foreach BOOST_FOREACH
140 #define MAP_IDX(sx, i, j) ((sx) * (j) + (i))
143 map_to_odom_(
tf::Transform(
tf::createQuaternionFromRPY( 0, 0, 0 ),
tf::
Point(0, 0, 0 ))),
144 laser_count_(0), private_nh_(
"~"), scan_filter_sub_(NULL), scan_filter_(NULL), transform_thread_(NULL)
151 map_to_odom_(
tf::Transform(
tf::createQuaternionFromRPY( 0, 0, 0 ),
tf::
Point(0, 0, 0 ))),
152 laser_count_(0),node_(nh), private_nh_(pnh), scan_filter_sub_(NULL), scan_filter_(NULL), transform_thread_(NULL)
159 map_to_odom_(
tf::Transform(
tf::createQuaternionFromRPY( 0, 0, 0 ),
tf::
Point(0, 0, 0 ))),
160 laser_count_(0), private_nh_(
"~"), scan_filter_sub_(NULL), scan_filter_(NULL), transform_thread_(NULL),
161 seed_(seed), tf_(
ros::Duration(max_duration_buffer))
284 double transform_publish_period;
294 std::vector<std::string> topics;
295 topics.push_back(std::string(
"/tf"));
296 topics.push_back(scan_topic);
300 std::queue<std::pair<sensor_msgs::LaserScan::ConstPtr, std::string> > s_queue;
303 tf::tfMessage::ConstPtr cur_tf = m.
instantiate<tf::tfMessage>();
304 if (cur_tf != NULL) {
305 for (
size_t i = 0; i < cur_tf->transforms.size(); ++i)
307 geometry_msgs::TransformStamped transformStamped;
309 transformStamped = cur_tf->transforms[i];
315 sensor_msgs::LaserScan::ConstPtr
s = m.
instantiate<sensor_msgs::LaserScan>();
319 s_queue.push(std::make_pair(
s,
""));
322 if (s_queue.size() > 5) {
330 while (!s_queue.empty())
343 s_queue.front().second = std::string(e.what());
353 if(transform_publish_period == 0)
356 ros::Rate r(1.0 / transform_publish_period);
394 ROS_WARN(
"Failed to compute odom pose, skipping scan (%s)", e.what());
414 ident.
stamp_ = scan.header.stamp;
421 ROS_WARN(
"Failed to compute laser pose, aborting initialization (%s)",
428 v.setValue(0, 0, 1 + laser_pose.
getOrigin().z());
434 ROS_DEBUG(
"Z-Axis in sensor frame: %.3f", up.z());
438 ROS_WARN(
"Unable to determine orientation of laser: %s",
444 if (fabs(fabs(up.z()) - 1) > 0.001)
446 ROS_WARN(
"Laser has to be mounted planar! Z-coordinate has to be 1 or -1, but gave: %.5f",
453 double angle_center = (scan.angle_min + scan.angle_max)/2;
460 ROS_INFO(
"Laser is mounted upwards.");
467 ROS_INFO(
"Laser is mounted upside down.");
473 double theta = - std::fabs(scan.angle_min - scan.angle_max)/2;
474 for(
unsigned int i=0; i<scan.ranges.size(); ++i)
477 theta += std::fabs(scan.angle_increment);
480 ROS_DEBUG(
"Laser angles in laser-frame: min: %.3f max: %.3f inc: %.3f", scan.angle_min, scan.angle_max,
481 scan.angle_increment);
482 ROS_DEBUG(
"Laser angles in top-down centered laser-frame: min: %.3f max: %.3f inc: %.3f",
laser_angles_.front(),
501 fabs(scan.angle_increment),
519 ROS_WARN(
"Unable to determine inital pose of laser! Starting point will be set to zero.");
530 gsp_->setgenerateMap(
false);
545 ROS_INFO(
"Initialization complete");
560 double* ranges_double =
new double[scan.ranges.size()];
565 int num_ranges = scan.ranges.size();
566 for(
int i=0; i < num_ranges; i++)
569 if(scan.ranges[num_ranges - i - 1] < scan.range_min)
570 ranges_double[i] = (double)scan.range_max;
572 ranges_double[i] = (
double)scan.ranges[num_ranges - i - 1];
576 for(
unsigned int i=0; i < scan.ranges.size(); i++)
579 if(scan.ranges[i] < scan.range_min)
580 ranges_double[i] = (double)scan.range_max;
582 ranges_double[i] = (
double)scan.ranges[i];
589 scan.header.stamp.toSec());
593 delete[] ranges_double;
633 ROS_DEBUG(
"new best pose: %.3f %.3f %.3f", mpose.x, mpose.y, mpose.
theta);
634 ROS_DEBUG(
"odom pose: %.3f %.3f %.3f", odom_pose.x, odom_pose.y, odom_pose.
theta);
635 ROS_DEBUG(
"correction: %.3f %.3f %.3f", mpose.x - odom_pose.x, mpose.y - odom_pose.y, mpose.
theta - odom_pose.
theta);
647 last_map_update = scan->header.stamp;
657 double weight_total=0.0;
658 for(std::vector<GMapping::GridSlamProcessor::Particle>::const_iterator it =
gsp_->
getParticles().begin();
662 weight_total += it->weight;
664 double entropy = 0.0;
665 for(std::vector<GMapping::GridSlamProcessor::Particle>::const_iterator it =
gsp_->
getParticles().begin();
669 if(it->weight/weight_total > 0.0)
670 entropy += it->weight/weight_total * log(it->weight/weight_total);
679 boost::mutex::scoped_lock map_lock (
map_mutex_);
687 matcher.setgenerateMap(
true);
691 std_msgs::Float64 entropy;
693 if(entropy.data > 0.0)
698 map_.map.info.origin.position.x = 0.0;
699 map_.map.info.origin.position.y = 0.0;
700 map_.map.info.origin.position.z = 0.0;
701 map_.map.info.origin.orientation.x = 0.0;
702 map_.map.info.origin.orientation.y = 0.0;
703 map_.map.info.origin.orientation.z = 0.0;
704 map_.map.info.origin.orientation.w = 1.0;
750 map_.map.data.resize(
map_.map.info.width *
map_.map.info.height);
752 ROS_DEBUG(
"map origin: (%f, %f)",
map_.map.info.origin.position.x,
map_.map.info.origin.position.y);
761 double occ=smap.
cell(p);
786 nav_msgs::GetMap::Response &res)
788 boost::mutex::scoped_lock map_lock (
map_mutex_);