slam_gmapping.h
Go to the documentation of this file.
1 /*
2  * slam_gmapping
3  * Copyright (c) 2008, Willow Garage, Inc.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  * * Redistributions of source code must retain the above copyright notice,
8  * this list of conditions and the following disclaimer.
9  * * Redistributions in binary form must reproduce the above copyright
10  * notice, this list of conditions and the following disclaimer in the
11  * documentation and/or other materials provided with the distribution.
12  * * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its
13  * contributors may be used to endorse or promote products derived from
14  * this software without specific prior written permission.
15  *
16  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
17  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
18  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
19  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
20  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
21  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
22  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
23  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
24  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
25  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
26  * POSSIBILITY OF SUCH DAMAGE.
27  *
28  */
29 
30 /* Author: Brian Gerkey */
31 
32 #include "ros/ros.h"
33 #include "sensor_msgs/LaserScan.h"
34 #include "std_msgs/Float64.h"
35 #include "nav_msgs/GetMap.h"
36 #include "tf/transform_listener.h"
39 #include "tf/message_filter.h"
40 
43 
44 #include <boost/thread.hpp>
45 
47 {
48  public:
49  SlamGMapping();
51  SlamGMapping(unsigned long int seed, unsigned long int max_duration_buffer);
52  ~SlamGMapping();
53 
54  void init();
55  void startLiveSlam();
56  void startReplay(const std::string & bag_fname, std::string scan_topic);
57  void publishTransform();
58 
59  void laserCallback(const sensor_msgs::LaserScan::ConstPtr& scan);
60  bool mapCallback(nav_msgs::GetMap::Request &req,
61  nav_msgs::GetMap::Response &res);
62  void publishLoop(double transform_publish_period);
63 
64  private:
74 
77  // The angles in the laser, going from -x to x (adjustment is made to get the laser between
78  // symmetrical bounds as that's what gmapping expects)
79  std::vector<double> laser_angles_;
80  // The pose, in the original laser frame, of the corresponding centered laser with z facing up
82  // Depending on the order of the elements in the scan and the orientation of the scan frame,
83  // We might need to change the order of the scan
85  unsigned int gsp_laser_beam_count_;
87 
89 
90  bool got_map_;
91  nav_msgs::GetMap::Response map_;
92 
95  boost::mutex map_to_odom_mutex_;
96  boost::mutex map_mutex_;
97 
100 
101  boost::thread* transform_thread_;
102 
103  std::string base_frame_;
104  std::string laser_frame_;
105  std::string map_frame_;
106  std::string odom_frame_;
107 
108  void updateMap(const sensor_msgs::LaserScan& scan);
109  bool getOdomPose(GMapping::OrientedPoint& gmap_pose, const ros::Time& t);
110  bool initMapper(const sensor_msgs::LaserScan& scan);
111  bool addScan(const sensor_msgs::LaserScan& scan, GMapping::OrientedPoint& gmap_pose);
112  double computePoseEntropy();
113 
114  // Parameters used by GMapping
115  double maxRange_;
116  double maxUrange_;
117  double maxrange_;
119  double sigma_;
121  double lstep_;
122  double astep_;
124  double lsigma_;
125  double ogain_;
126  int lskip_;
127  double srr_;
128  double srt_;
129  double str_;
130  double stt_;
136  double xmin_;
137  double ymin_;
138  double xmax_;
139  double ymax_;
140  double delta_;
141  double occ_thresh_;
146 
148 
149  unsigned long int seed_;
150 
152  double tf_delay_;
153 };
SlamGMapping::seed_
unsigned long int seed_
Definition: slam_gmapping.h:149
SlamGMapping::str_
double str_
Definition: slam_gmapping.h:129
ros::Publisher
SlamGMapping::getOdomPose
bool getOdomPose(GMapping::OrientedPoint &gmap_pose, const ros::Time &t)
Definition: slam_gmapping.cpp:382
SlamGMapping::SlamGMapping
SlamGMapping()
Definition: slam_gmapping.cpp:142
SlamGMapping::throttle_scans_
int throttle_scans_
Definition: slam_gmapping.h:99
SlamGMapping::tf_
tf::TransformListener tf_
Definition: slam_gmapping.h:70
SlamGMapping::gsp_laser_
GMapping::RangeSensor * gsp_laser_
Definition: slam_gmapping.h:76
SlamGMapping::scan_filter_
tf::MessageFilter< sensor_msgs::LaserScan > * scan_filter_
Definition: slam_gmapping.h:72
SlamGMapping::computePoseEntropy
double computePoseEntropy()
Definition: slam_gmapping.cpp:655
SlamGMapping::updateMap
void updateMap(const sensor_msgs::LaserScan &scan)
Definition: slam_gmapping.cpp:676
ros.h
SlamGMapping::publishTransform
void publishTransform()
Definition: slam_gmapping.cpp:798
SlamGMapping::gsp_laser_beam_count_
unsigned int gsp_laser_beam_count_
Definition: slam_gmapping.h:85
SlamGMapping::do_reverse_range_
bool do_reverse_range_
Definition: slam_gmapping.h:84
SlamGMapping::laser_count_
int laser_count_
Definition: slam_gmapping.h:98
SlamGMapping
Definition: slam_gmapping.h:46
SlamGMapping::delta_
double delta_
Definition: slam_gmapping.h:140
SlamGMapping::initMapper
bool initMapper(const sensor_msgs::LaserScan &scan)
Definition: slam_gmapping.cpp:406
SlamGMapping::srr_
double srr_
Definition: slam_gmapping.h:127
SlamGMapping::gsp_odom_
GMapping::OdometrySensor * gsp_odom_
Definition: slam_gmapping.h:86
SlamGMapping::got_map_
bool got_map_
Definition: slam_gmapping.h:90
SlamGMapping::centered_laser_pose_
tf::Stamped< tf::Pose > centered_laser_pose_
Definition: slam_gmapping.h:81
SlamGMapping::node_
ros::NodeHandle node_
Definition: slam_gmapping.h:65
transform_broadcaster.h
SlamGMapping::ss_
ros::ServiceServer ss_
Definition: slam_gmapping.h:69
SlamGMapping::sigma_
double sigma_
Definition: slam_gmapping.h:119
SlamGMapping::got_first_scan_
bool got_first_scan_
Definition: slam_gmapping.h:88
SlamGMapping::tfB_
tf::TransformBroadcaster * tfB_
Definition: slam_gmapping.h:73
message_filters::Subscriber< sensor_msgs::LaserScan >
ros::ServiceServer
SlamGMapping::maxrange_
double maxrange_
Definition: slam_gmapping.h:117
tf::Stamped
SlamGMapping::map_update_interval_
ros::Duration map_update_interval_
Definition: slam_gmapping.h:93
SlamGMapping::temporalUpdate_
double temporalUpdate_
Definition: slam_gmapping.h:133
SlamGMapping::llsamplestep_
double llsamplestep_
Definition: slam_gmapping.h:143
SlamGMapping::entropy_publisher_
ros::Publisher entropy_publisher_
Definition: slam_gmapping.h:66
SlamGMapping::lskip_
int lskip_
Definition: slam_gmapping.h:126
message_filter.h
SlamGMapping::minimum_score_
double minimum_score_
Definition: slam_gmapping.h:118
SlamGMapping::ogain_
double ogain_
Definition: slam_gmapping.h:125
GMapping::GridSlamProcessor
tf::TransformBroadcaster
SlamGMapping::map_mutex_
boost::mutex map_mutex_
Definition: slam_gmapping.h:96
SlamGMapping::startReplay
void startReplay(const std::string &bag_fname, std::string scan_topic)
Definition: slam_gmapping.cpp:282
subscriber.h
SlamGMapping::map_to_odom_
tf::Transform map_to_odom_
Definition: slam_gmapping.h:94
SlamGMapping::stt_
double stt_
Definition: slam_gmapping.h:130
SlamGMapping::xmin_
double xmin_
Definition: slam_gmapping.h:136
SlamGMapping::maxRange_
double maxRange_
Definition: slam_gmapping.h:115
SlamGMapping::angularUpdate_
double angularUpdate_
Definition: slam_gmapping.h:132
sensor.h
SlamGMapping::addScan
bool addScan(const sensor_msgs::LaserScan &scan, GMapping::OrientedPoint &gmap_pose)
Definition: slam_gmapping.cpp:551
tf::Transform
SlamGMapping::scan_filter_sub_
message_filters::Subscriber< sensor_msgs::LaserScan > * scan_filter_sub_
Definition: slam_gmapping.h:71
SlamGMapping::ymax_
double ymax_
Definition: slam_gmapping.h:139
SlamGMapping::base_frame_
std::string base_frame_
Definition: slam_gmapping.h:103
SlamGMapping::srt_
double srt_
Definition: slam_gmapping.h:128
SlamGMapping::lstep_
double lstep_
Definition: slam_gmapping.h:121
SlamGMapping::startLiveSlam
void startLiveSlam()
Definition: slam_gmapping.cpp:269
SlamGMapping::resampleThreshold_
double resampleThreshold_
Definition: slam_gmapping.h:134
SlamGMapping::occ_thresh_
double occ_thresh_
Definition: slam_gmapping.h:141
SlamGMapping::llsamplerange_
double llsamplerange_
Definition: slam_gmapping.h:142
SlamGMapping::lasamplestep_
double lasamplestep_
Definition: slam_gmapping.h:145
transform_listener.h
SlamGMapping::sstm_
ros::Publisher sstm_
Definition: slam_gmapping.h:68
SlamGMapping::map_to_odom_mutex_
boost::mutex map_to_odom_mutex_
Definition: slam_gmapping.h:95
ros::Time
SlamGMapping::publishLoop
void publishLoop(double transform_publish_period)
Definition: slam_gmapping.cpp:352
SlamGMapping::tf_delay_
double tf_delay_
Definition: slam_gmapping.h:152
SlamGMapping::private_nh_
ros::NodeHandle private_nh_
Definition: slam_gmapping.h:147
tf::MessageFilter< sensor_msgs::LaserScan >
gridslamprocessor.h
tf::TransformListener
SlamGMapping::linearUpdate_
double linearUpdate_
Definition: slam_gmapping.h:131
SlamGMapping::transform_thread_
boost::thread * transform_thread_
Definition: slam_gmapping.h:101
SlamGMapping::lsigma_
double lsigma_
Definition: slam_gmapping.h:124
SlamGMapping::iterations_
int iterations_
Definition: slam_gmapping.h:123
SlamGMapping::~SlamGMapping
~SlamGMapping()
Definition: slam_gmapping.cpp:363
SlamGMapping::laser_frame_
std::string laser_frame_
Definition: slam_gmapping.h:104
SlamGMapping::sst_
ros::Publisher sst_
Definition: slam_gmapping.h:67
SlamGMapping::maxUrange_
double maxUrange_
Definition: slam_gmapping.h:116
SlamGMapping::transform_publish_period_
double transform_publish_period_
Definition: slam_gmapping.h:151
GMapping::RangeSensor
SlamGMapping::xmax_
double xmax_
Definition: slam_gmapping.h:138
orientedpoint< double, double >
SlamGMapping::odom_frame_
std::string odom_frame_
Definition: slam_gmapping.h:106
SlamGMapping::mapCallback
bool mapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
Definition: slam_gmapping.cpp:785
SlamGMapping::init
void init()
Definition: slam_gmapping.cpp:167
ros::Duration
SlamGMapping::kernelSize_
int kernelSize_
Definition: slam_gmapping.h:120
SlamGMapping::map_
nav_msgs::GetMap::Response map_
Definition: slam_gmapping.h:91
SlamGMapping::map_frame_
std::string map_frame_
Definition: slam_gmapping.h:105
GMapping::OdometrySensor
SlamGMapping::astep_
double astep_
Definition: slam_gmapping.h:122
SlamGMapping::lasamplerange_
double lasamplerange_
Definition: slam_gmapping.h:144
SlamGMapping::laser_angles_
std::vector< double > laser_angles_
Definition: slam_gmapping.h:79
ros::NodeHandle
SlamGMapping::laserCallback
void laserCallback(const sensor_msgs::LaserScan::ConstPtr &scan)
Definition: slam_gmapping.cpp:610
SlamGMapping::particles_
int particles_
Definition: slam_gmapping.h:135
SlamGMapping::gsp_
GMapping::GridSlamProcessor * gsp_
Definition: slam_gmapping.h:75
SlamGMapping::ymin_
double ymin_
Definition: slam_gmapping.h:137


gmapping
Author(s): Brian Gerkey
autogenerated on Wed Aug 21 2024 02:12:11