#include <slam_gmapping.h>
Public Member Functions | |
void | init () |
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 (ros::NodeHandle &nh, ros::NodeHandle &pnh) | |
SlamGMapping (unsigned long int seed, unsigned long int max_duration_buffer) | |
void | startLiveSlam () |
void | startReplay (const std::string &bag_fname, std::string scan_topic) |
~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) |
Definition at line 33 of file slam_gmapping.h.
SlamGMapping::SlamGMapping | ( | ) |
Definition at line 129 of file slam_gmapping.cpp.
SlamGMapping::SlamGMapping | ( | ros::NodeHandle & | nh, |
ros::NodeHandle & | pnh | ||
) |
Definition at line 137 of file slam_gmapping.cpp.
SlamGMapping::SlamGMapping | ( | unsigned long int | seed, |
unsigned long int | max_duration_buffer | ||
) |
SlamGMapping::~SlamGMapping | ( | ) |
Definition at line 350 of file slam_gmapping.cpp.
|
private |
Definition at line 538 of file slam_gmapping.cpp.
|
private |
Definition at line 642 of file slam_gmapping.cpp.
|
private |
Definition at line 369 of file slam_gmapping.cpp.
void SlamGMapping::init | ( | ) |
Definition at line 154 of file slam_gmapping.cpp.
|
private |
Definition at line 393 of file slam_gmapping.cpp.
void SlamGMapping::laserCallback | ( | const sensor_msgs::LaserScan::ConstPtr & | scan | ) |
Definition at line 597 of file slam_gmapping.cpp.
bool SlamGMapping::mapCallback | ( | nav_msgs::GetMap::Request & | req, |
nav_msgs::GetMap::Response & | res | ||
) |
Definition at line 772 of file slam_gmapping.cpp.
void SlamGMapping::publishLoop | ( | double | transform_publish_period | ) |
Definition at line 339 of file slam_gmapping.cpp.
void SlamGMapping::publishTransform | ( | ) |
Definition at line 785 of file slam_gmapping.cpp.
void SlamGMapping::startLiveSlam | ( | ) |
Definition at line 256 of file slam_gmapping.cpp.
void SlamGMapping::startReplay | ( | const std::string & | bag_fname, |
std::string | scan_topic | ||
) |
Definition at line 269 of file slam_gmapping.cpp.
|
private |
Definition at line 663 of file slam_gmapping.cpp.
|
private |
Definition at line 119 of file slam_gmapping.h.
|
private |
Definition at line 109 of file slam_gmapping.h.
|
private |
Definition at line 90 of file slam_gmapping.h.
|
private |
Definition at line 68 of file slam_gmapping.h.
|
private |
Definition at line 127 of file slam_gmapping.h.
|
private |
Definition at line 71 of file slam_gmapping.h.
|
private |
Definition at line 53 of file slam_gmapping.h.
|
private |
Definition at line 75 of file slam_gmapping.h.
|
private |
Definition at line 77 of file slam_gmapping.h.
|
private |
Definition at line 62 of file slam_gmapping.h.
|
private |
Definition at line 63 of file slam_gmapping.h.
|
private |
Definition at line 72 of file slam_gmapping.h.
|
private |
Definition at line 73 of file slam_gmapping.h.
|
private |
Definition at line 110 of file slam_gmapping.h.
|
private |
Definition at line 107 of file slam_gmapping.h.
|
private |
Definition at line 131 of file slam_gmapping.h.
|
private |
Definition at line 132 of file slam_gmapping.h.
|
private |
Definition at line 66 of file slam_gmapping.h.
|
private |
Definition at line 85 of file slam_gmapping.h.
|
private |
Definition at line 91 of file slam_gmapping.h.
|
private |
Definition at line 118 of file slam_gmapping.h.
|
private |
Definition at line 129 of file slam_gmapping.h.
|
private |
Definition at line 130 of file slam_gmapping.h.
|
private |
Definition at line 111 of file slam_gmapping.h.
|
private |
Definition at line 113 of file slam_gmapping.h.
|
private |
Definition at line 108 of file slam_gmapping.h.
|
private |
Definition at line 78 of file slam_gmapping.h.
|
private |
Definition at line 92 of file slam_gmapping.h.
|
private |
Definition at line 83 of file slam_gmapping.h.
|
private |
Definition at line 81 of file slam_gmapping.h.
|
private |
Definition at line 82 of file slam_gmapping.h.
|
private |
Definition at line 80 of file slam_gmapping.h.
|
private |
Definition at line 102 of file slam_gmapping.h.
|
private |
Definition at line 104 of file slam_gmapping.h.
|
private |
Definition at line 103 of file slam_gmapping.h.
|
private |
Definition at line 105 of file slam_gmapping.h.
|
private |
Definition at line 52 of file slam_gmapping.h.
|
private |
Definition at line 128 of file slam_gmapping.h.
|
private |
Definition at line 93 of file slam_gmapping.h.
|
private |
Definition at line 112 of file slam_gmapping.h.
|
private |
Definition at line 122 of file slam_gmapping.h.
|
private |
Definition at line 134 of file slam_gmapping.h.
|
private |
Definition at line 121 of file slam_gmapping.h.
|
private |
Definition at line 59 of file slam_gmapping.h.
|
private |
Definition at line 58 of file slam_gmapping.h.
|
private |
Definition at line 136 of file slam_gmapping.h.
|
private |
Definition at line 106 of file slam_gmapping.h.
|
private |
Definition at line 114 of file slam_gmapping.h.
|
private |
Definition at line 115 of file slam_gmapping.h.
|
private |
Definition at line 56 of file slam_gmapping.h.
|
private |
Definition at line 54 of file slam_gmapping.h.
|
private |
Definition at line 55 of file slam_gmapping.h.
|
private |
Definition at line 116 of file slam_gmapping.h.
|
private |
Definition at line 117 of file slam_gmapping.h.
|
private |
Definition at line 120 of file slam_gmapping.h.
|
private |
Definition at line 57 of file slam_gmapping.h.
|
private |
Definition at line 139 of file slam_gmapping.h.
|
private |
Definition at line 60 of file slam_gmapping.h.
|
private |
Definition at line 86 of file slam_gmapping.h.
|
private |
Definition at line 138 of file slam_gmapping.h.
|
private |
Definition at line 88 of file slam_gmapping.h.
|
private |
Definition at line 125 of file slam_gmapping.h.
|
private |
Definition at line 123 of file slam_gmapping.h.
|
private |
Definition at line 126 of file slam_gmapping.h.
|
private |
Definition at line 124 of file slam_gmapping.h.