#include <slam_gmapping.h>
| Public Member Functions | |
| void | laserCallback (const sensor_msgs::LaserScan::ConstPtr &scan) | 
| bool | mapCallback (nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res) | 
| void | publishLoop (double transform_publish_period) | 
| void | publishTransform () | 
| SlamGMapping () | |
| ~SlamGMapping () | |
| Private Member Functions | |
| bool | addScan (const sensor_msgs::LaserScan &scan, GMapping::OrientedPoint &gmap_pose) | 
| double | computePoseEntropy () | 
| bool | getOdomPose (GMapping::OrientedPoint &gmap_pose, const ros::Time &t) | 
| bool | initMapper (const sensor_msgs::LaserScan &scan) | 
| void | updateMap (const sensor_msgs::LaserScan &scan) | 
| Private Attributes | |
| double | angle_max_ | 
| double | angle_min_ | 
| double | angularUpdate_ | 
| double | astep_ | 
| std::string | base_frame_ | 
| double | delta_ | 
| ros::Publisher | entropy_publisher_ | 
| bool | got_first_scan_ | 
| bool | got_map_ | 
| GMapping::GridSlamProcessor * | gsp_ | 
| GMapping::RangeSensor * | gsp_laser_ | 
| double | gsp_laser_angle_increment_ | 
| unsigned int | gsp_laser_beam_count_ | 
| GMapping::OdometrySensor * | gsp_odom_ | 
| int | iterations_ | 
| int | kernelSize_ | 
| double | lasamplerange_ | 
| double | lasamplestep_ | 
| int | laser_count_ | 
| std::string | laser_frame_ | 
| double | linearUpdate_ | 
| double | llsamplerange_ | 
| double | llsamplestep_ | 
| double | lsigma_ | 
| int | lskip_ | 
| double | lstep_ | 
| nav_msgs::GetMap::Response | map_ | 
| std::string | map_frame_ | 
| boost::mutex | map_mutex_ | 
| tf::Transform | map_to_odom_ | 
| boost::mutex | map_to_odom_mutex_ | 
| ros::Duration | map_update_interval_ | 
| double | maxRange_ | 
| double | maxrange_ | 
| double | maxUrange_ | 
| ros::NodeHandle | node_ | 
| double | occ_thresh_ | 
| std::string | odom_frame_ | 
| double | ogain_ | 
| int | particles_ | 
| double | resampleThreshold_ | 
| tf::MessageFilter < sensor_msgs::LaserScan > * | scan_filter_ | 
| message_filters::Subscriber < sensor_msgs::LaserScan > * | scan_filter_sub_ | 
| double | sigma_ | 
| double | srr_ | 
| double | srt_ | 
| ros::ServiceServer | ss_ | 
| ros::Publisher | sst_ | 
| ros::Publisher | sstm_ | 
| double | str_ | 
| double | stt_ | 
| double | temporalUpdate_ | 
| tf::TransformListener | tf_ | 
| double | tf_delay_ | 
| tf::TransformBroadcaster * | tfB_ | 
| int | throttle_scans_ | 
| boost::thread * | transform_thread_ | 
| double | xmax_ | 
| double | xmin_ | 
| double | ymax_ | 
| double | ymin_ | 
Definition at line 33 of file slam_gmapping.h.
Definition at line 123 of file slam_gmapping.cpp.
Definition at line 246 of file slam_gmapping.cpp.
| bool SlamGMapping::addScan | ( | const sensor_msgs::LaserScan & | scan, | 
| GMapping::OrientedPoint & | gmap_pose | ||
| ) |  [private] | 
Definition at line 418 of file slam_gmapping.cpp.
| double SlamGMapping::computePoseEntropy | ( | ) |  [private] | 
Definition at line 519 of file slam_gmapping.cpp.
| bool SlamGMapping::getOdomPose | ( | GMapping::OrientedPoint & | gmap_pose, | 
| const ros::Time & | t | ||
| ) |  [private] | 
Definition at line 265 of file slam_gmapping.cpp.
| bool SlamGMapping::initMapper | ( | const sensor_msgs::LaserScan & | scan | ) |  [private] | 
Definition at line 289 of file slam_gmapping.cpp.
| void SlamGMapping::laserCallback | ( | const sensor_msgs::LaserScan::ConstPtr & | scan | ) | 
Definition at line 476 of file slam_gmapping.cpp.
| bool SlamGMapping::mapCallback | ( | nav_msgs::GetMap::Request & | req, | 
| nav_msgs::GetMap::Response & | res | ||
| ) | 
Definition at line 659 of file slam_gmapping.cpp.
| void SlamGMapping::publishLoop | ( | double | transform_publish_period | ) | 
Definition at line 235 of file slam_gmapping.cpp.
| void SlamGMapping::publishTransform | ( | ) | 
Definition at line 672 of file slam_gmapping.cpp.
| void SlamGMapping::updateMap | ( | const sensor_msgs::LaserScan & | scan | ) |  [private] | 
Definition at line 540 of file slam_gmapping.cpp.
| double SlamGMapping::angle_max_  [private] | 
Definition at line 61 of file slam_gmapping.h.
| double SlamGMapping::angle_min_  [private] | 
Definition at line 60 of file slam_gmapping.h.
| double SlamGMapping::angularUpdate_  [private] | 
Definition at line 108 of file slam_gmapping.h.
| double SlamGMapping::astep_  [private] | 
Definition at line 98 of file slam_gmapping.h.
| std::string SlamGMapping::base_frame_  [private] | 
Definition at line 80 of file slam_gmapping.h.
| double SlamGMapping::delta_  [private] | 
Definition at line 116 of file slam_gmapping.h.
Definition at line 48 of file slam_gmapping.h.
| bool SlamGMapping::got_first_scan_  [private] | 
Definition at line 65 of file slam_gmapping.h.
| bool SlamGMapping::got_map_  [private] | 
Definition at line 67 of file slam_gmapping.h.
| GMapping::GridSlamProcessor* SlamGMapping::gsp_  [private] | 
Definition at line 57 of file slam_gmapping.h.
| GMapping::RangeSensor* SlamGMapping::gsp_laser_  [private] | 
Definition at line 58 of file slam_gmapping.h.
| double SlamGMapping::gsp_laser_angle_increment_  [private] | 
Definition at line 59 of file slam_gmapping.h.
| unsigned int SlamGMapping::gsp_laser_beam_count_  [private] | 
Definition at line 62 of file slam_gmapping.h.
| GMapping::OdometrySensor* SlamGMapping::gsp_odom_  [private] | 
Definition at line 63 of file slam_gmapping.h.
| int SlamGMapping::iterations_  [private] | 
Definition at line 99 of file slam_gmapping.h.
| int SlamGMapping::kernelSize_  [private] | 
Definition at line 96 of file slam_gmapping.h.
| double SlamGMapping::lasamplerange_  [private] | 
Definition at line 120 of file slam_gmapping.h.
| double SlamGMapping::lasamplestep_  [private] | 
Definition at line 121 of file slam_gmapping.h.
| int SlamGMapping::laser_count_  [private] | 
Definition at line 75 of file slam_gmapping.h.
| std::string SlamGMapping::laser_frame_  [private] | 
Definition at line 81 of file slam_gmapping.h.
| double SlamGMapping::linearUpdate_  [private] | 
Definition at line 107 of file slam_gmapping.h.
| double SlamGMapping::llsamplerange_  [private] | 
Definition at line 118 of file slam_gmapping.h.
| double SlamGMapping::llsamplestep_  [private] | 
Definition at line 119 of file slam_gmapping.h.
| double SlamGMapping::lsigma_  [private] | 
Definition at line 100 of file slam_gmapping.h.
| int SlamGMapping::lskip_  [private] | 
Definition at line 102 of file slam_gmapping.h.
| double SlamGMapping::lstep_  [private] | 
Definition at line 97 of file slam_gmapping.h.
| nav_msgs::GetMap::Response SlamGMapping::map_  [private] | 
Definition at line 68 of file slam_gmapping.h.
| std::string SlamGMapping::map_frame_  [private] | 
Definition at line 82 of file slam_gmapping.h.
| boost::mutex SlamGMapping::map_mutex_  [private] | 
Definition at line 73 of file slam_gmapping.h.
| tf::Transform SlamGMapping::map_to_odom_  [private] | 
Definition at line 71 of file slam_gmapping.h.
| boost::mutex SlamGMapping::map_to_odom_mutex_  [private] | 
Definition at line 72 of file slam_gmapping.h.
Definition at line 70 of file slam_gmapping.h.
| double SlamGMapping::maxRange_  [private] | 
Definition at line 92 of file slam_gmapping.h.
| double SlamGMapping::maxrange_  [private] | 
Definition at line 94 of file slam_gmapping.h.
| double SlamGMapping::maxUrange_  [private] | 
Definition at line 93 of file slam_gmapping.h.
| ros::NodeHandle SlamGMapping::node_  [private] | 
Definition at line 47 of file slam_gmapping.h.
| double SlamGMapping::occ_thresh_  [private] | 
Definition at line 117 of file slam_gmapping.h.
| std::string SlamGMapping::odom_frame_  [private] | 
Definition at line 83 of file slam_gmapping.h.
| double SlamGMapping::ogain_  [private] | 
Definition at line 101 of file slam_gmapping.h.
| int SlamGMapping::particles_  [private] | 
Definition at line 111 of file slam_gmapping.h.
| double SlamGMapping::resampleThreshold_  [private] | 
Definition at line 110 of file slam_gmapping.h.
| tf::MessageFilter<sensor_msgs::LaserScan>* SlamGMapping::scan_filter_  [private] | 
Definition at line 54 of file slam_gmapping.h.
| message_filters::Subscriber<sensor_msgs::LaserScan>* SlamGMapping::scan_filter_sub_  [private] | 
Definition at line 53 of file slam_gmapping.h.
| double SlamGMapping::sigma_  [private] | 
Definition at line 95 of file slam_gmapping.h.
| double SlamGMapping::srr_  [private] | 
Definition at line 103 of file slam_gmapping.h.
| double SlamGMapping::srt_  [private] | 
Definition at line 104 of file slam_gmapping.h.
| ros::ServiceServer SlamGMapping::ss_  [private] | 
Definition at line 51 of file slam_gmapping.h.
| ros::Publisher SlamGMapping::sst_  [private] | 
Definition at line 49 of file slam_gmapping.h.
| ros::Publisher SlamGMapping::sstm_  [private] | 
Definition at line 50 of file slam_gmapping.h.
| double SlamGMapping::str_  [private] | 
Definition at line 105 of file slam_gmapping.h.
| double SlamGMapping::stt_  [private] | 
Definition at line 106 of file slam_gmapping.h.
| double SlamGMapping::temporalUpdate_  [private] | 
Definition at line 109 of file slam_gmapping.h.
| tf::TransformListener SlamGMapping::tf_  [private] | 
Definition at line 52 of file slam_gmapping.h.
| double SlamGMapping::tf_delay_  [private] | 
Definition at line 123 of file slam_gmapping.h.
| tf::TransformBroadcaster* SlamGMapping::tfB_  [private] | 
Definition at line 55 of file slam_gmapping.h.
| int SlamGMapping::throttle_scans_  [private] | 
Definition at line 76 of file slam_gmapping.h.
| boost::thread* SlamGMapping::transform_thread_  [private] | 
Definition at line 78 of file slam_gmapping.h.
| double SlamGMapping::xmax_  [private] | 
Definition at line 114 of file slam_gmapping.h.
| double SlamGMapping::xmin_  [private] | 
Definition at line 112 of file slam_gmapping.h.
| double SlamGMapping::ymax_  [private] | 
Definition at line 115 of file slam_gmapping.h.
| double SlamGMapping::ymin_  [private] | 
Definition at line 113 of file slam_gmapping.h.