Newer
Older
Niklas Yann Wettengel
committed
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
#ifndef SLAM_NODE_H
#define SLAM_NODE_H
#include <vector>
#include <map>
#include "Math/Pose.h"
#include "tf/transform_broadcaster.h"
#include "sensor_msgs/LaserScan.h"
#include "nav_msgs/Odometry.h"
#include "nav_msgs/OccupancyGrid.h"
#include "geometry_msgs/Pose.h"
#include "std_msgs/Empty.h"
#include "std_msgs/Bool.h"
#include "geometry_msgs/PoseWithCovarianceStamped.h"
class OccupancyMap;
class SlamFilter;
class HyperSlamFilter;
/**
* @class SlamNode
*
* @author Malte Knauf, Stephan Wirth, Susanne Maur (RX), David Gossow (RX),
* Christian Fuchs (R12), Nicolai Wojke (R14), Susanne Thierfelder (R16)
*
*
* @brief The Simultaneous localization and mapping module
*
* This module receives odometry and laser data and computes the
* robot's position and a map out of this data. Then it sends a
* geometry_msgs/PoseStamped and nav_msgs/OccupancyGrid message.
*/
class SlamNode
{
public:
/**
* The constructor adds the message types and prepares the module for receiving them.
*/
SlamNode(ros::NodeHandle *nh);
/**
* This method initializes the member variables.
*/
virtual void init();
/**
* The destructor deletes the filter thread instance.
*/
virtual ~SlamNode();
private:
/**
* Callback methods for all incoming messages
*/
void callbackLaserScan( const sensor_msgs::LaserScan::ConstPtr& msg );
void callbackOdometry( const nav_msgs::Odometry::ConstPtr& msg );
void callbackUserDefPose( const geometry_msgs::Pose::ConstPtr& msg );
void callbackDoMapping( const std_msgs::Bool::ConstPtr& msg );
void callbackResetMap( const std_msgs::Empty::ConstPtr& msg );
void callbackLoadedMap( const nav_msgs::OccupancyGrid::ConstPtr& msg );
void callbackMasking( const nav_msgs::OccupancyGrid::ConstPtr& msg );
void callbackResetHigh(const std_msgs::Empty::ConstPtr& msg);
void callbackInitialPose(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& msg);
/**
* This function resets the current maps to the initial state.
*/
void resetMaps();
/**
* This function processes the current odometry data in combination with the
* last send odometry and laser informations to pass on corresponding data
* to the filter threads.
*
* @param odoTime timestamp of this odometry data
* @param currentOdometryPose the current odometry measurements of the robot
*/
void processMeasurements(ros::Time odoTime, Pose currentOdometryPose);
/**
* This method retrieves the current map of the slam filter and sends a map
* data message containing the map.
*/
void sendMapDataMessage();
/**
* This method gets the current position from the filter thread and sends it
* in a position data message.
*/
void sendPositionDataMessage();
/**
* This variable stores the identification number of a GetPositionDataM.
* It is needed for a correct response message.
*/
unsigned int m_LastLaserMessageId;
/**
* This variables stores the last odometry measurement as reference that is used
* to compute the pose of the robot during a specific laserscan.
*/
Pose m_ReferenceOdometryPose;
/**
* This variable stores the time of the last odometry measurement as reference
* which is used to compute the pose of the robot during a specific laserscan.
*/
ros::Time m_ReferenceOdometryTime;
/**
* This variable stores the time the last map message was sent to be able to
* compute the time for the next map send.
*/
ros::Time m_LastMapSendTime;
ros::Time m_LastPositionSendTime;
/**
* This variable stores the last laser measurement.
*/
sensor_msgs::LaserScanConstPtr m_LastLaserData;
/**
* This variable stores the time of last laser measurement.
*/
ros::Time m_LaserDataTime;
/**
* time stamp of last particle filter step
*/
ros::Time m_LastMappingTime;
/**
* This variable stores a pointer to the hyper slam filter
*/
HyperSlamFilter* m_HyperSlamFilter;
/**
* Scatter variances in self localization.
*/
double m_ScatterVarXY;
double m_ScatterVarTheta;
/**
* This variabe is true, if the slam algorithm is used for mapping and
* keeps updating the map, false otherwise.
*/
bool m_DoMapping;
/**
* duration to wait between two particle filter steps
*/
ros::Duration m_WaitDuration;
/**
* Broadcasts the transform map -> base_link
*/
tf::TransformBroadcaster m_tfBroadcaster;
/**
* subscribers and publishers
*/
ros::Subscriber m_LaserScanSubscriber;
ros::Subscriber m_OdometrySubscriber;
ros::Subscriber m_UserDefPoseSubscriber;
ros::Subscriber m_DoMappingSubscriber;
ros::Subscriber m_ResetMapSubscriber;
ros::Subscriber m_LoadMapSubscriber;
ros::Subscriber m_MaskingSubscriber;
ros::Subscriber m_ResetHighSubscriber;
ros::Subscriber m_InitialPoseSubscriber;
ros::Publisher m_PoseStampedPublisher;
ros::Publisher m_SLAMMapPublisher;
};
#endif