116 #include "nav_msgs/MapMetaData.h" 118 #include "gmapping/sensor/sensor_range/rangesensor.h" 119 #include "gmapping/sensor/sensor_odometry/odometrysensor.h" 123 #include <boost/foreach.hpp> 124 #define foreach BOOST_FOREACH 127 #define MAP_IDX(sx, i, j) ((sx) * (j) + (i)) 130 map_to_odom_(
tf::Transform(
tf::createQuaternionFromRPY( 0, 0, 0 ),
tf::
Point(0, 0, 0 ))),
131 laser_count_(0), private_nh_(
"~"), scan_filter_sub_(NULL), scan_filter_(NULL), transform_thread_(NULL)
160 gsp_ =
new GMapping::GridSlamProcessor();
271 double transform_publish_period;
281 std::vector<std::string> topics;
282 topics.push_back(std::string(
"/tf"));
283 topics.push_back(scan_topic);
287 std::queue<std::pair<sensor_msgs::LaserScan::ConstPtr, std::string> > s_queue;
290 tf::tfMessage::ConstPtr cur_tf = m.
instantiate<tf::tfMessage>();
291 if (cur_tf != NULL) {
292 for (
size_t i = 0; i < cur_tf->transforms.size(); ++i)
294 geometry_msgs::TransformStamped transformStamped;
296 transformStamped = cur_tf->transforms[i];
302 sensor_msgs::LaserScan::ConstPtr
s = m.
instantiate<sensor_msgs::LaserScan>();
304 if (!(
ros::Time(s->header.stamp)).is_zero())
306 s_queue.push(std::make_pair(s,
""));
309 if (s_queue.size() > 5) {
317 while (!s_queue.empty())
330 s_queue.front().second = std::string(e.what());
340 if(transform_publish_period == 0)
343 ros::Rate r(1.0 / transform_publish_period);
381 ROS_WARN(
"Failed to compute odom pose, skipping scan (%s)", e.what());
384 double yaw =
tf::getYaw(odom_pose.getRotation());
386 gmap_pose = GMapping::OrientedPoint(odom_pose.getOrigin().x(),
387 odom_pose.getOrigin().y(),
401 ident.
stamp_ = scan.header.stamp;
408 ROS_WARN(
"Failed to compute laser pose, aborting initialization (%s)",
415 v.
setValue(0, 0, 1 + laser_pose.getOrigin().z());
421 ROS_DEBUG(
"Z-Axis in sensor frame: %.3f", up.z());
425 ROS_WARN(
"Unable to determine orientation of laser: %s",
431 if (fabs(fabs(up.z()) - 1) > 0.001)
433 ROS_WARN(
"Laser has to be mounted planar! Z-coordinate has to be 1 or -1, but gave: %.5f",
440 double angle_center = (scan.angle_min + scan.angle_max)/2;
447 ROS_INFO(
"Laser is mounted upwards.");
454 ROS_INFO(
"Laser is mounted upside down.");
460 double theta = - std::fabs(scan.angle_min - scan.angle_max)/2;
461 for(
unsigned int i=0; i<scan.ranges.size(); ++i)
464 theta += std::fabs(scan.angle_increment);
467 ROS_DEBUG(
"Laser angles in laser-frame: min: %.3f max: %.3f inc: %.3f", scan.angle_min, scan.angle_max,
468 scan.angle_increment);
469 ROS_DEBUG(
"Laser angles in top-down centered laser-frame: min: %.3f max: %.3f inc: %.3f",
laser_angles_.front(),
472 GMapping::OrientedPoint gmap_pose(0, 0, 0);
486 gsp_laser_ =
new GMapping::RangeSensor(
"FLASER",
488 fabs(scan.angle_increment),
494 GMapping::SensorMap smap;
496 gsp_->setSensorMap(smap);
503 GMapping::OrientedPoint initialPose;
506 ROS_WARN(
"Unable to determine inital pose of laser! Starting point will be set to zero.");
507 initialPose = GMapping::OrientedPoint(0.0, 0.0, 0.0);
517 gsp_->setgenerateMap(
false);
530 GMapping::sampleGaussian(1,
seed_);
532 ROS_INFO(
"Initialization complete");
547 double* ranges_double =
new double[scan.ranges.size()];
552 int num_ranges = scan.ranges.size();
553 for(
int i=0; i < num_ranges; i++)
556 if(scan.ranges[num_ranges - i - 1] < scan.range_min)
557 ranges_double[i] = (double)scan.range_max;
559 ranges_double[i] = (
double)scan.ranges[num_ranges - i - 1];
563 for(
unsigned int i=0; i < scan.ranges.size(); i++)
566 if(scan.ranges[i] < scan.range_min)
567 ranges_double[i] = (double)scan.range_max;
569 ranges_double[i] = (
double)scan.ranges[i];
573 GMapping::RangeReading reading(scan.ranges.size(),
576 scan.header.stamp.toSec());
580 delete[] ranges_double;
582 reading.setPose(gmap_pose);
593 return gsp_->processScan(reading);
613 GMapping::OrientedPoint odom_pose;
619 GMapping::OrientedPoint mpose =
gsp_->getParticles()[
gsp_->getBestParticleIndex()].pose;
620 ROS_DEBUG(
"new best pose: %.3f %.3f %.3f", mpose.x, mpose.y, mpose.theta);
621 ROS_DEBUG(
"odom pose: %.3f %.3f %.3f", odom_pose.x, odom_pose.y, odom_pose.theta);
622 ROS_DEBUG(
"correction: %.3f %.3f %.3f", mpose.x - odom_pose.x, mpose.y - odom_pose.y, mpose.theta - odom_pose.theta);
634 last_map_update = scan->header.stamp;
644 double weight_total=0.0;
645 for(std::vector<GMapping::GridSlamProcessor::Particle>::const_iterator it =
gsp_->getParticles().begin();
646 it !=
gsp_->getParticles().end();
649 weight_total += it->weight;
651 double entropy = 0.0;
652 for(std::vector<GMapping::GridSlamProcessor::Particle>::const_iterator it =
gsp_->getParticles().begin();
653 it !=
gsp_->getParticles().end();
656 if(it->weight/weight_total > 0.0)
657 entropy += it->weight/weight_total * log(it->weight/weight_total);
666 boost::mutex::scoped_lock map_lock (
map_mutex_);
667 GMapping::ScanMatcher matcher;
669 matcher.setLaserParameters(scan.ranges.size(), &(
laser_angles_[0]),
674 matcher.setgenerateMap(
true);
676 GMapping::GridSlamProcessor::Particle best =
677 gsp_->getParticles()[
gsp_->getBestParticleIndex()];
678 std_msgs::Float64 entropy;
680 if(entropy.data > 0.0)
685 map_.map.info.origin.position.x = 0.0;
686 map_.map.info.origin.position.y = 0.0;
687 map_.map.info.origin.position.z = 0.0;
688 map_.map.info.origin.orientation.x = 0.0;
689 map_.map.info.origin.orientation.y = 0.0;
690 map_.map.info.origin.orientation.z = 0.0;
691 map_.map.info.origin.orientation.w = 1.0;
694 GMapping::Point center;
702 for(GMapping::GridSlamProcessor::TNode* n = best.node;
715 matcher.invalidateActiveArea();
716 matcher.computeActiveArea(smap, n->pose, &((*n->reading)[0]));
717 matcher.registerScan(smap, n->pose, &((*n->reading)[0]));
721 if(
map_.map.info.width != (
unsigned int) smap.getMapSizeX() ||
map_.map.info.height != (
unsigned int) smap.getMapSizeY()) {
725 GMapping::Point wmin = smap.map2world(GMapping::IntPoint(0, 0));
726 GMapping::Point wmax = smap.map2world(GMapping::IntPoint(smap.getMapSizeX(), smap.getMapSizeY()));
730 ROS_DEBUG(
"map size is now %dx%d pixels (%f,%f)-(%f, %f)", smap.getMapSizeX(), smap.getMapSizeY(),
733 map_.map.info.width = smap.getMapSizeX();
734 map_.map.info.height = smap.getMapSizeY();
737 map_.map.data.resize(
map_.map.info.width *
map_.map.info.height);
739 ROS_DEBUG(
"map origin: (%f, %f)",
map_.map.info.origin.position.x,
map_.map.info.origin.position.y);
742 for(
int x=0;
x < smap.getMapSizeX();
x++)
744 for(
int y=0;
y < smap.getMapSizeY();
y++)
747 GMapping::IntPoint p(
x,
y);
748 double occ=smap.cell(p);
773 nav_msgs::GetMap::Response &res)
775 boost::mutex::scoped_lock map_lock (
map_mutex_);
bool mapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
void laserCallback(const sensor_msgs::LaserScan::ConstPtr &scan)
static tf::Quaternion createQuaternionFromRPY(double roll, double pitch, double yaw)
message_filters::Subscriber< sensor_msgs::LaserScan > * scan_filter_sub_
bool initMapper(const sensor_msgs::LaserScan &scan)
void updateMap(const sensor_msgs::LaserScan &scan)
void publish(const boost::shared_ptr< M > &message) const
tf::TransformListener tf_
void open(std::string const &filename, uint32_t mode=bagmode::Read)
double computePoseEntropy()
static double getYaw(const Quaternion &bt_q)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
TFSIMD_FORCE_INLINE const tfScalar & y() const
void publishLoop(double transform_publish_period)
TFSIMD_FORCE_INLINE void setValue(const tfScalar &x, const tfScalar &y, const tfScalar &z)
bool getOdomPose(GMapping::OrientedPoint &gmap_pose, const ros::Time &t)
tf::Stamped< tf::Pose > centered_laser_pose_
unsigned int gsp_laser_beam_count_
tf::TransformBroadcaster * tfB_
void startReplay(const std::string &bag_fname, std::string scan_topic)
tf::Transform map_to_odom_
Duration & fromSec(double t)
nav_msgs::GetMap::Response map_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
TFSIMD_FORCE_INLINE Quaternion inverse(const Quaternion &q)
boost::shared_ptr< T > instantiate() const
boost::mutex map_to_odom_mutex_
boost::thread * transform_thread_
ros::Publisher entropy_publisher_
TFSIMD_FORCE_INLINE const tfScalar & x() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROS_WARN_STREAM(args)
ros::Duration map_update_interval_
double transform_publish_period_
#define MAP_IDX(sx, i, j)
ros::NodeHandle private_nh_
GMapping::GridSlamProcessor * gsp_
bool getParam(const std::string &key, std::string &s) const
double resampleThreshold_
static void transformStampedMsgToTF(const geometry_msgs::TransformStamped &msg, StampedTransform &bt)
std::vector< double > laser_angles_
tf::MessageFilter< sensor_msgs::LaserScan > * scan_filter_
GMapping::OdometrySensor * gsp_odom_
GMapping::RangeSensor * gsp_laser_
bool addScan(const sensor_msgs::LaserScan &scan, GMapping::OrientedPoint &gmap_pose)
Connection registerCallback(const C &callback)