Public Member Functions | Private Member Functions | Private Attributes
SlamGMapping Class Reference

#include <slam_gmapping.h>

List of all members.

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)

Private Attributes

double angularUpdate_
double astep_
std::string base_frame_
tf::Stamped< tf::Posecentered_laser_pose_
double delta_
bool do_reverse_range_
ros::Publisher entropy_publisher_
bool got_first_scan_
bool got_map_
GMapping::GridSlamProcessorgsp_
GMapping::RangeSensorgsp_laser_
unsigned int gsp_laser_beam_count_
GMapping::OdometrySensorgsp_odom_
int iterations_
int kernelSize_
double lasamplerange_
double lasamplestep_
std::vector< double > laser_angles_
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_
double minimum_score_
ros::NodeHandle node_
double occ_thresh_
std::string odom_frame_
double ogain_
int particles_
ros::NodeHandle private_nh_
double resampleThreshold_
tf::MessageFilter
< sensor_msgs::LaserScan > * 
scan_filter_
message_filters::Subscriber
< sensor_msgs::LaserScan > * 
scan_filter_sub_
unsigned long int seed_
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::TransformBroadcastertfB_
int throttle_scans_
double transform_publish_period_
boost::thread * transform_thread_
double xmax_
double xmin_
double ymax_
double ymin_

Detailed Description

Definition at line 33 of file slam_gmapping.h.


Constructor & Destructor Documentation

Definition at line 129 of file slam_gmapping.cpp.

Definition at line 137 of file slam_gmapping.cpp.

SlamGMapping::SlamGMapping ( unsigned long int  seed,
unsigned long int  max_duration_buffer 
)

Definition at line 350 of file slam_gmapping.cpp.


Member Function Documentation

bool SlamGMapping::addScan ( const sensor_msgs::LaserScan &  scan,
GMapping::OrientedPoint gmap_pose 
) [private]

Definition at line 538 of file slam_gmapping.cpp.

double SlamGMapping::computePoseEntropy ( ) [private]

Definition at line 642 of file slam_gmapping.cpp.

bool SlamGMapping::getOdomPose ( GMapping::OrientedPoint gmap_pose,
const ros::Time t 
) [private]

Definition at line 369 of file slam_gmapping.cpp.

Definition at line 154 of file slam_gmapping.cpp.

bool SlamGMapping::initMapper ( const sensor_msgs::LaserScan &  scan) [private]
Todo:
Expose setting an initial pose
Todo:
Check these calls; in the gmapping gui, they use llsamplestep and llsamplerange intead of lasamplestep and lasamplerange. It was probably a typo, but who knows.

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.

Definition at line 785 of file slam_gmapping.cpp.

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.

void SlamGMapping::updateMap ( const sensor_msgs::LaserScan &  scan) [private]
Todo:
Sort out the unknown vs. free vs. obstacle thresholding

Definition at line 663 of file slam_gmapping.cpp.


Member Data Documentation

double SlamGMapping::angularUpdate_ [private]

Definition at line 119 of file slam_gmapping.h.

double SlamGMapping::astep_ [private]

Definition at line 109 of file slam_gmapping.h.

std::string SlamGMapping::base_frame_ [private]

Definition at line 90 of file slam_gmapping.h.

Definition at line 68 of file slam_gmapping.h.

double SlamGMapping::delta_ [private]

Definition at line 127 of file slam_gmapping.h.

Definition at line 71 of file slam_gmapping.h.

Definition at line 53 of file slam_gmapping.h.

Definition at line 75 of file slam_gmapping.h.

bool SlamGMapping::got_map_ [private]

Definition at line 77 of file slam_gmapping.h.

Definition at line 62 of file slam_gmapping.h.

Definition at line 63 of file slam_gmapping.h.

unsigned int SlamGMapping::gsp_laser_beam_count_ [private]

Definition at line 72 of file slam_gmapping.h.

Definition at line 73 of file slam_gmapping.h.

Definition at line 110 of file slam_gmapping.h.

Definition at line 107 of file slam_gmapping.h.

double SlamGMapping::lasamplerange_ [private]

Definition at line 131 of file slam_gmapping.h.

double SlamGMapping::lasamplestep_ [private]

Definition at line 132 of file slam_gmapping.h.

std::vector<double> SlamGMapping::laser_angles_ [private]

Definition at line 66 of file slam_gmapping.h.

Definition at line 85 of file slam_gmapping.h.

std::string SlamGMapping::laser_frame_ [private]

Definition at line 91 of file slam_gmapping.h.

double SlamGMapping::linearUpdate_ [private]

Definition at line 118 of file slam_gmapping.h.

double SlamGMapping::llsamplerange_ [private]

Definition at line 129 of file slam_gmapping.h.

double SlamGMapping::llsamplestep_ [private]

Definition at line 130 of file slam_gmapping.h.

double SlamGMapping::lsigma_ [private]

Definition at line 111 of file slam_gmapping.h.

int SlamGMapping::lskip_ [private]

Definition at line 113 of file slam_gmapping.h.

double SlamGMapping::lstep_ [private]

Definition at line 108 of file slam_gmapping.h.

nav_msgs::GetMap::Response SlamGMapping::map_ [private]

Definition at line 78 of file slam_gmapping.h.

std::string SlamGMapping::map_frame_ [private]

Definition at line 92 of file slam_gmapping.h.

boost::mutex SlamGMapping::map_mutex_ [private]

Definition at line 83 of file slam_gmapping.h.

Definition at line 81 of file slam_gmapping.h.

boost::mutex SlamGMapping::map_to_odom_mutex_ [private]

Definition at line 82 of file slam_gmapping.h.

Definition at line 80 of file slam_gmapping.h.

double SlamGMapping::maxRange_ [private]

Definition at line 102 of file slam_gmapping.h.

double SlamGMapping::maxrange_ [private]

Definition at line 104 of file slam_gmapping.h.

double SlamGMapping::maxUrange_ [private]

Definition at line 103 of file slam_gmapping.h.

double SlamGMapping::minimum_score_ [private]

Definition at line 105 of file slam_gmapping.h.

Definition at line 52 of file slam_gmapping.h.

double SlamGMapping::occ_thresh_ [private]

Definition at line 128 of file slam_gmapping.h.

std::string SlamGMapping::odom_frame_ [private]

Definition at line 93 of file slam_gmapping.h.

double SlamGMapping::ogain_ [private]

Definition at line 112 of file slam_gmapping.h.

int SlamGMapping::particles_ [private]

Definition at line 122 of file slam_gmapping.h.

Definition at line 134 of file slam_gmapping.h.

Definition at line 121 of file slam_gmapping.h.

tf::MessageFilter<sensor_msgs::LaserScan>* SlamGMapping::scan_filter_ [private]

Definition at line 59 of file slam_gmapping.h.

message_filters::Subscriber<sensor_msgs::LaserScan>* SlamGMapping::scan_filter_sub_ [private]

Definition at line 58 of file slam_gmapping.h.

unsigned long int SlamGMapping::seed_ [private]

Definition at line 136 of file slam_gmapping.h.

double SlamGMapping::sigma_ [private]

Definition at line 106 of file slam_gmapping.h.

double SlamGMapping::srr_ [private]

Definition at line 114 of file slam_gmapping.h.

double SlamGMapping::srt_ [private]

Definition at line 115 of file slam_gmapping.h.

Definition at line 56 of file slam_gmapping.h.

Definition at line 54 of file slam_gmapping.h.

Definition at line 55 of file slam_gmapping.h.

double SlamGMapping::str_ [private]

Definition at line 116 of file slam_gmapping.h.

double SlamGMapping::stt_ [private]

Definition at line 117 of file slam_gmapping.h.

Definition at line 120 of file slam_gmapping.h.

Definition at line 57 of file slam_gmapping.h.

double SlamGMapping::tf_delay_ [private]

Definition at line 139 of file slam_gmapping.h.

Definition at line 60 of file slam_gmapping.h.

Definition at line 86 of file slam_gmapping.h.

Definition at line 138 of file slam_gmapping.h.

boost::thread* SlamGMapping::transform_thread_ [private]

Definition at line 88 of file slam_gmapping.h.

double SlamGMapping::xmax_ [private]

Definition at line 125 of file slam_gmapping.h.

double SlamGMapping::xmin_ [private]

Definition at line 123 of file slam_gmapping.h.

double SlamGMapping::ymax_ [private]

Definition at line 126 of file slam_gmapping.h.

double SlamGMapping::ymin_ [private]

Definition at line 124 of file slam_gmapping.h.


The documentation for this class was generated from the following files:


gmapping
Author(s): Brian Gerkey
autogenerated on Sat Jun 8 2019 19:40:34