slam_gmapping.h
Go to the documentation of this file.
1 /*
2  * slam_gmapping
3  * Copyright (c) 2008, Willow Garage, Inc.
4  *
5  * THE WORK (AS DEFINED BELOW) IS PROVIDED UNDER THE TERMS OF THIS CREATIVE
6  * COMMONS PUBLIC LICENSE ("CCPL" OR "LICENSE"). THE WORK IS PROTECTED BY
7  * COPYRIGHT AND/OR OTHER APPLICABLE LAW. ANY USE OF THE WORK OTHER THAN AS
8  * AUTHORIZED UNDER THIS LICENSE OR COPYRIGHT LAW IS PROHIBITED.
9  *
10  * BY EXERCISING ANY RIGHTS TO THE WORK PROVIDED HERE, YOU ACCEPT AND AGREE TO
11  * BE BOUND BY THE TERMS OF THIS LICENSE. THE LICENSOR GRANTS YOU THE RIGHTS
12  * CONTAINED HERE IN CONSIDERATION OF YOUR ACCEPTANCE OF SUCH TERMS AND
13  * CONDITIONS.
14  *
15  */
16 
17 /* Author: Brian Gerkey */
18 
19 #include "ros/ros.h"
20 #include "sensor_msgs/LaserScan.h"
21 #include "std_msgs/Float64.h"
22 #include "nav_msgs/GetMap.h"
23 #include "tf/transform_listener.h"
26 #include "tf/message_filter.h"
27 
30 
31 #include <boost/thread.hpp>
32 
34 {
35  public:
36  SlamGMapping();
38  SlamGMapping(unsigned long int seed, unsigned long int max_duration_buffer);
39  ~SlamGMapping();
40 
41  void init();
42  void startLiveSlam();
43  void startReplay(const std::string & bag_fname, std::string scan_topic);
44  void publishTransform();
45 
46  void laserCallback(const sensor_msgs::LaserScan::ConstPtr& scan);
47  bool mapCallback(nav_msgs::GetMap::Request &req,
48  nav_msgs::GetMap::Response &res);
49  void publishLoop(double transform_publish_period);
50 
51  private:
61 
64  // The angles in the laser, going from -x to x (adjustment is made to get the laser between
65  // symmetrical bounds as that's what gmapping expects)
66  std::vector<double> laser_angles_;
67  // The pose, in the original laser frame, of the corresponding centered laser with z facing up
69  // Depending on the order of the elements in the scan and the orientation of the scan frame,
70  // We might need to change the order of the scan
72  unsigned int gsp_laser_beam_count_;
74 
76 
77  bool got_map_;
78  nav_msgs::GetMap::Response map_;
79 
82  boost::mutex map_to_odom_mutex_;
83  boost::mutex map_mutex_;
84 
87 
88  boost::thread* transform_thread_;
89 
90  std::string base_frame_;
91  std::string laser_frame_;
92  std::string map_frame_;
93  std::string odom_frame_;
94 
95  void updateMap(const sensor_msgs::LaserScan& scan);
96  bool getOdomPose(GMapping::OrientedPoint& gmap_pose, const ros::Time& t);
97  bool initMapper(const sensor_msgs::LaserScan& scan);
98  bool addScan(const sensor_msgs::LaserScan& scan, GMapping::OrientedPoint& gmap_pose);
99  double computePoseEntropy();
100 
101  // Parameters used by GMapping
102  double maxRange_;
103  double maxUrange_;
104  double maxrange_;
106  double sigma_;
108  double lstep_;
109  double astep_;
111  double lsigma_;
112  double ogain_;
113  int lskip_;
114  double srr_;
115  double srt_;
116  double str_;
117  double stt_;
123  double xmin_;
124  double ymin_;
125  double xmax_;
126  double ymax_;
127  double delta_;
128  double occ_thresh_;
133 
135 
136  unsigned long int seed_;
137 
139  double tf_delay_;
140 };
bool mapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
void laserCallback(const sensor_msgs::LaserScan::ConstPtr &scan)
message_filters::Subscriber< sensor_msgs::LaserScan > * scan_filter_sub_
Definition: slam_gmapping.h:58
double linearUpdate_
bool initMapper(const sensor_msgs::LaserScan &scan)
void updateMap(const sensor_msgs::LaserScan &scan)
tf::TransformListener tf_
Definition: slam_gmapping.h:57
double lasamplerange_
ros::ServiceServer ss_
Definition: slam_gmapping.h:56
double angularUpdate_
std::string odom_frame_
Definition: slam_gmapping.h:93
double computePoseEntropy()
std::string laser_frame_
Definition: slam_gmapping.h:91
double occ_thresh_
double lasamplestep_
ros::Publisher sst_
Definition: slam_gmapping.h:54
double llsamplestep_
unsigned long int seed_
void publishLoop(double transform_publish_period)
bool got_first_scan_
Definition: slam_gmapping.h:75
bool do_reverse_range_
Definition: slam_gmapping.h:71
bool getOdomPose(GMapping::OrientedPoint &gmap_pose, const ros::Time &t)
tf::Stamped< tf::Pose > centered_laser_pose_
Definition: slam_gmapping.h:68
unsigned int gsp_laser_beam_count_
Definition: slam_gmapping.h:72
double tf_delay_
tf::TransformBroadcaster * tfB_
Definition: slam_gmapping.h:60
void startReplay(const std::string &bag_fname, std::string scan_topic)
boost::mutex map_mutex_
Definition: slam_gmapping.h:83
tf::Transform map_to_odom_
Definition: slam_gmapping.h:81
void startLiveSlam()
nav_msgs::GetMap::Response map_
Definition: slam_gmapping.h:78
double llsamplerange_
double maxUrange_
double temporalUpdate_
boost::mutex map_to_odom_mutex_
Definition: slam_gmapping.h:82
boost::thread * transform_thread_
Definition: slam_gmapping.h:88
ros::Publisher entropy_publisher_
Definition: slam_gmapping.h:53
ros::Duration map_update_interval_
Definition: slam_gmapping.h:80
double transform_publish_period_
ros::NodeHandle private_nh_
GMapping::GridSlamProcessor * gsp_
Definition: slam_gmapping.h:62
double maxrange_
double resampleThreshold_
ros::Publisher sstm_
Definition: slam_gmapping.h:55
void publishTransform()
std::string base_frame_
Definition: slam_gmapping.h:90
std::string map_frame_
Definition: slam_gmapping.h:92
double maxRange_
std::vector< double > laser_angles_
Definition: slam_gmapping.h:66
ros::NodeHandle node_
Definition: slam_gmapping.h:52
double minimum_score_
tf::MessageFilter< sensor_msgs::LaserScan > * scan_filter_
Definition: slam_gmapping.h:59
GMapping::OdometrySensor * gsp_odom_
Definition: slam_gmapping.h:73
GMapping::RangeSensor * gsp_laser_
Definition: slam_gmapping.h:63
bool addScan(const sensor_msgs::LaserScan &scan, GMapping::OrientedPoint &gmap_pose)


gmapping
Author(s): Brian Gerkey
autogenerated on Mon Jun 10 2019 15:08:12