SelfLocalizer.h
Go to the documentation of this file.
1 #ifndef SELF_LOCALIZER_H
2 #define SELF_LOCALIZER_H
3 
4 #include <string>
5 
6 #include <ros/ros.h>
8 #include <nav_msgs/OccupancyGrid.h>
9 #include <geometry_msgs/PoseArray.h>
10 #include <sensor_msgs/LaserScan.h>
11 
12 #include <nav2d_localizer/map.h>
13 #include <nav2d_localizer/pf.h>
14 #include <nav2d_localizer/pf_pdf.h>
15 
17 {
18 public:
19  OdometryData(const tf::StampedTransform& pNewPose, const tf::StampedTransform& pLastPose);
20 
21  double mDeltaX;
22  double mDeltaY;
23  double mDeltaTheta;
24 };
25 
26 class LaserData
27 {
28 public:
29  LaserData(const sensor_msgs::LaserScan::ConstPtr& scan);
30  ~LaserData();
31 
33  double mRangeMax;
34  double (*mRanges)[2];
35 };
36 
38 {
39 public:
40  SelfLocalizer(bool publish = true);
42 
43  bool initialize();
44 
45  // Uniformly distribute particles in the map
46  static pf_vector_t distributeParticles(void* map);
47 
48  // Create a map from a ROS OccupancyGrid
49  void convertMap(const nav_msgs::OccupancyGrid& map_msg);
50 
51  void process(const sensor_msgs::LaserScan::ConstPtr& scan);
52 
53  double getCovariance();
55 
57  {
59  }
60 
61  void publishParticleCloud();
62 
63  // These methods are static, so the particle filter can call them via callback.
64  // The parameters are static, so they can be used within these two methods.
65  static double calculateMoveModel(OdometryData* data, pf_sample_set_t* set);
66  static double calculateBeamModel(LaserData *data, pf_sample_set_t* set);
67  static double calculateLikelihoodFieldModel(LaserData *data, pf_sample_set_t* set);
68 
69 private:
70  // Parameters for movement model (I don't know what they do.)
71  static double sAlpha1, sAlpha2, sAlpha3, sAlpha4;
73 
74  // How many range readings from every scan are used for the sensor model update
75  static int sMaxBeams;
76 
77  // Max distance at which we care about obstacles for constructing the likelihood field
78  static double sLikelihoodMaxDist;
79 
80  // The map
81  static map_t* sMap;
82 
83  // Stddev of Gaussian model for laser hits
84  static double sSigmaHit;
85 
86  // Decay rate of exponential model for short readings
87  static double sLamdaShort;
88 
89  // Mixture params for the components of the model, must sum to 1
90  static double sZHit;
91  static double sZShort;
92  static double sZMax;
93  static double sZRand;
94 
95  std::string mMapFrame;
96  std::string mOdometryFrame;
97  std::string mRobotFrame;
98  std::string mLaserFrame;
99 
100 private:
101  // The actual particle filter
104 
105  // ROS stuff
108 
109  // The pose of the last scan used for localization
111 
112  // The current localization result
114 
115  // Parameters
118  double mAlphaSlow;
119  double mAlphaFast;
121  double mPopulationZ;
122 
124  double mMinRotation;
125 
128 
129  int mLaserModelType; // 1 = beam, 2 = likelihood field
130 
133 };
134 
135 #endif
SelfLocalizer::mRobotFrame
std::string mRobotFrame
Definition: SelfLocalizer.h:97
SelfLocalizer::~SelfLocalizer
~SelfLocalizer()
Definition: SelfLocalizer.cpp:146
SelfLocalizer::convertMap
void convertMap(const nav_msgs::OccupancyGrid &map_msg)
Definition: SelfLocalizer.cpp:466
SelfLocalizer::process
void process(const sensor_msgs::LaserScan::ConstPtr &scan)
Definition: SelfLocalizer.cpp:393
SelfLocalizer::getCovariance
double getCovariance()
Definition: SelfLocalizer.cpp:501
LaserData::mRangeMax
double mRangeMax
Definition: SelfLocalizer.h:33
ros::Publisher
SelfLocalizer::mParticlePublisher
ros::Publisher mParticlePublisher
Definition: SelfLocalizer.h:107
pf.h
pf_vector_t
Definition: pf_vector.h:38
SelfLocalizer::initialize
bool initialize()
Definition: SelfLocalizer.cpp:357
SelfLocalizer::publishParticleCloud
void publishParticleCloud()
Definition: SelfLocalizer.cpp:556
SelfLocalizer::SelfLocalizer
SelfLocalizer(bool publish=true)
Definition: SelfLocalizer.cpp:80
SelfLocalizer::mLastPose
static tf::StampedTransform mLastPose
Definition: SelfLocalizer.h:110
ros.h
SelfLocalizer::sZShort
static double sZShort
Definition: SelfLocalizer.h:91
SelfLocalizer::mAlphaSlow
double mAlphaSlow
Definition: SelfLocalizer.h:118
OdometryData::mDeltaX
double mDeltaX
Definition: SelfLocalizer.h:21
SelfLocalizer::sLamdaShort
static double sLamdaShort
Definition: SelfLocalizer.h:87
SelfLocalizer::mMinRotation
double mMinRotation
Definition: SelfLocalizer.h:124
SelfLocalizer::mMinTranslation
double mMinTranslation
Definition: SelfLocalizer.h:123
SelfLocalizer::sZRand
static double sZRand
Definition: SelfLocalizer.h:93
LaserData
Definition: SelfLocalizer.h:26
SelfLocalizer::sLaserPose
static pf_vector_t sLaserPose
Definition: SelfLocalizer.h:72
SelfLocalizer::calculateLikelihoodFieldModel
static double calculateLikelihoodFieldModel(LaserData *data, pf_sample_set_t *set)
Definition: SelfLocalizer.cpp:282
OdometryData
Definition: SelfLocalizer.h:16
SelfLocalizer::sLikelihoodMaxDist
static double sLikelihoodMaxDist
Definition: SelfLocalizer.h:78
SelfLocalizer::mParticleFilter
pf_t * mParticleFilter
Definition: SelfLocalizer.h:102
_pf_sample_set_t
Definition: pf.h:90
tf::StampedTransform
SelfLocalizer::sAlpha1
static double sAlpha1
Definition: SelfLocalizer.h:71
SelfLocalizer::mProcessedScans
int mProcessedScans
Definition: SelfLocalizer.h:103
SelfLocalizer::mAlphaFast
double mAlphaFast
Definition: SelfLocalizer.h:119
SelfLocalizer::sZHit
static double sZHit
Definition: SelfLocalizer.h:90
_pf_t
Definition: pf.h:111
pf_sensor_model_fn_t
double(* pf_sensor_model_fn_t)(void *sensor_data, struct _pf_sample_set_t *set)
Definition: pf.h:54
SelfLocalizer::getBestPose
tf::Transform getBestPose()
Definition: SelfLocalizer.cpp:510
SelfLocalizer::mPopulationZ
double mPopulationZ
Definition: SelfLocalizer.h:121
LaserData::mRangeCount
int mRangeCount
Definition: SelfLocalizer.h:32
SelfLocalizer::mMinParticles
int mMinParticles
Definition: SelfLocalizer.h:116
SelfLocalizer::mPopulationErr
double mPopulationErr
Definition: SelfLocalizer.h:120
SelfLocalizer::sAlpha4
static double sAlpha4
Definition: SelfLocalizer.h:71
LaserData::LaserData
LaserData(const sensor_msgs::LaserScan::ConstPtr &scan)
Definition: SelfLocalizer.cpp:33
SelfLocalizer::mLaserModelType
int mLaserModelType
Definition: SelfLocalizer.h:129
SelfLocalizer::mLaserFrame
std::string mLaserFrame
Definition: SelfLocalizer.h:98
SelfLocalizer
Definition: SelfLocalizer.h:37
map.h
OdometryData::OdometryData
OdometryData(const tf::StampedTransform &pNewPose, const tf::StampedTransform &pLastPose)
Definition: SelfLocalizer.cpp:26
SelfLocalizer::mMapFrame
std::string mMapFrame
Definition: SelfLocalizer.h:95
tf::Transform
SelfLocalizer::mSensorModelFunction
pf_sensor_model_fn_t mSensorModelFunction
Definition: SelfLocalizer.h:131
SelfLocalizer::mMaxParticles
int mMaxParticles
Definition: SelfLocalizer.h:117
SelfLocalizer::mOdometryFrame
std::string mOdometryFrame
Definition: SelfLocalizer.h:96
SelfLocalizer::sMaxBeams
static int sMaxBeams
Definition: SelfLocalizer.h:75
pf_pdf.h
SelfLocalizer::sSigmaHit
static double sSigmaHit
Definition: SelfLocalizer.h:84
SelfLocalizer::mFirstScanReceived
bool mFirstScanReceived
Definition: SelfLocalizer.h:127
OdometryData::mDeltaTheta
double mDeltaTheta
Definition: SelfLocalizer.h:23
transform_listener.h
LaserData::mRanges
double(* mRanges)[2]
Definition: SelfLocalizer.h:34
map_t
Definition: map.h:61
SelfLocalizer::mTransformListener
tf::TransformListener mTransformListener
Definition: SelfLocalizer.h:106
SelfLocalizer::distributeParticles
static pf_vector_t distributeParticles(void *map)
Definition: SelfLocalizer.cpp:154
LaserData::~LaserData
~LaserData()
Definition: SelfLocalizer.cpp:56
tf::TransformListener
OdometryData::mDeltaY
double mDeltaY
Definition: SelfLocalizer.h:22
SelfLocalizer::mPublishParticles
bool mPublishParticles
Definition: SelfLocalizer.h:126
SelfLocalizer::calculateMoveModel
static double calculateMoveModel(OdometryData *data, pf_sample_set_t *set)
Definition: SelfLocalizer.cpp:183
pf_action_model_fn_t
void(* pf_action_model_fn_t)(void *action_data, struct _pf_sample_set_t *set)
Definition: pf.h:49
SelfLocalizer::mMapToOdometry
tf::Transform mMapToOdometry
Definition: SelfLocalizer.h:113
SelfLocalizer::sAlpha3
static double sAlpha3
Definition: SelfLocalizer.h:71
SelfLocalizer::calculateBeamModel
static double calculateBeamModel(LaserData *data, pf_sample_set_t *set)
Definition: SelfLocalizer.cpp:225
SelfLocalizer::sAlpha2
static double sAlpha2
Definition: SelfLocalizer.h:71
SelfLocalizer::sMap
static map_t * sMap
Definition: SelfLocalizer.h:81
SelfLocalizer::mActionModelFunction
pf_action_model_fn_t mActionModelFunction
Definition: SelfLocalizer.h:132
ros::Time::now
static Time now()
SelfLocalizer::sZMax
static double sZMax
Definition: SelfLocalizer.h:92
SelfLocalizer::getMapToOdometry
tf::StampedTransform getMapToOdometry()
Definition: SelfLocalizer.h:56


nav2d_localizer
Author(s): Sebastian Kasperski
autogenerated on Wed Mar 2 2022 00:37:18