Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024 #ifndef GSP_THREAD_H
00025 #define GSP_THREAD_H
00026
00027 #include <unistd.h>
00028 #include <pthread.h>
00029 #include <deque>
00030 #include <fstream>
00031 #include <iostream>
00032 #include <log/carmenconfiguration.h>
00033 #include <log/sensorstream.h>
00034 #include <gridfastslam/gridslamprocessor.h>
00035
00036 using namespace std;
00037 using namespace GMapping;
00038
00039
00040 #define MAX_STRING_LENGTH 1024
00041
00042
00043 struct GridSlamProcessorThread : public GridSlamProcessor {
00044 struct Event{
00045 virtual ~Event();
00046 };
00047
00048 struct ParticleMoveEvent: public Event{
00049 bool scanmatched;
00050 double neff;
00051 std::vector<OrientedPoint> hypotheses;
00052 std::vector<double> weightSums;
00053 };
00054
00055 struct TruePosEvent : public Event{
00056 OrientedPoint pose;
00057 };
00058
00059 struct ResampleEvent: public Event{
00060 std::vector<unsigned int> indexes;
00061 };
00062
00063 struct MapEvent: public Event{
00064 ScanMatcherMap* pmap;
00065 unsigned int index;
00066 OrientedPoint pose;
00067 virtual ~MapEvent();
00068 };
00069
00070 struct DoneEvent: public Event{
00071 };
00072
00073 typedef deque<Event*> EventDeque;
00074
00075 GridSlamProcessorThread();
00076 ~GridSlamProcessorThread();
00077 int init(int argc, const char * const * argv);
00078 int loadFiles(const char * fn=0);
00079 static void * fastslamthread(GridSlamProcessorThread* gpt);
00080 std::vector<OrientedPoint> getHypotheses();
00081 std::vector<unsigned int> getIndexes();
00082
00083 EventDeque getEvents();
00084
00085 void start();
00086 void stop();
00087
00088 virtual void onOdometryUpdate();
00089 virtual void onResampleUpdate();
00090 virtual void onScanmatchUpdate();
00091
00092 virtual void syncOdometryUpdate();
00093 virtual void syncResampleUpdate();
00094 virtual void syncScanmatchUpdate();
00095
00096 void setEventBufferSize(unsigned int length);
00097 inline void setMapUpdateTime(unsigned int ut) {mapUpdateTime=ut;}
00098 inline bool isRunning() const {return running;}
00099 OrientedPoint boundingBox(SensorLog* log, double& xmin, double& ymin, double& xmax, double& ymax) const;
00100 private:
00101
00102 void addEvent(Event *);
00103 EventDeque eventBuffer;
00104
00105 unsigned int eventBufferLength;
00106 unsigned int mapUpdateTime;
00107 unsigned int mapTimer;
00108
00109
00110 std::vector<OrientedPoint> hypotheses;
00111 std::vector<unsigned int> indexes;
00112 std::vector<double> weightSums;
00113 pthread_mutex_t hp_mutex, ind_mutex, hist_mutex;
00114 pthread_t gfs_thread;
00115 bool running;
00116
00117
00118 std::string filename;
00119 std::string outfilename;
00120
00121 double xmin;
00122 double ymin;
00123 double xmax;
00124 double ymax;
00125 bool autosize;
00126 double delta;
00127 double resampleThreshold;
00128
00129
00130 double sigma;
00131 double maxrange;
00132 double maxUrange;
00133 double regscore;
00134 double lstep;
00135 double astep;
00136 int kernelSize;
00137 int iterations;
00138 double critscore;
00139 double maxMove;
00140 unsigned int lskip;
00141
00142
00143 double lsigma;
00144 double ogain;
00145 double llsamplerange, lasamplerange;
00146 double llsamplestep, lasamplestep;
00147 double linearOdometryReliability;
00148 double angularOdometryReliability;
00149
00150
00151
00152 double srr, srt, str, stt;
00153
00154 int particles;
00155 bool skipMatching;
00156
00157
00158 double angularUpdate;
00159 double linearUpdate;
00160
00161
00162 SensorMap sensorMap;
00163
00164 InputSensorStream* input;
00165 std::ifstream plainStream;
00166 bool readFromStdin;
00167 bool onLine;
00168 bool generateMap;
00169 bool considerOdometryCovariance;
00170 unsigned int randseed;
00171
00172
00173 const char* const * m_argv;
00174 unsigned int m_argc;
00175
00176 };
00177 #endif