RtabmapEvent.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2014, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #ifndef RTABMAPEVENT_H_
00029 #define RTABMAPEVENT_H_
00030 
00031 
00032 
00033 #include <rtabmap/utilite/UEvent.h>
00034 #include "rtabmap/core/Statistics.h"
00035 #include "rtabmap/core/Parameters.h"
00036 
00037 namespace rtabmap
00038 {
00039 
00041 class RtabmapEvent : public UEvent
00042 {
00043 public:
00044         RtabmapEvent(const Statistics & stats) :
00045                 UEvent(0),
00046                 _stats(stats) {}
00047 
00048         virtual ~RtabmapEvent() {}
00049         const Statistics & getStats() const {return _stats;}
00050         virtual std::string getClassName() const {return std::string("RtabmapEvent");}
00051 
00052 private:
00053         Statistics _stats;
00054 };
00055 
00056 class RtabmapEventCmd : public UEvent
00057 {
00058 public:
00059         enum dummy {d}; // Hack, to fix Eclipse complaining about not defined Cmd enum ?!
00060         enum Cmd {
00061                         kCmdInit,
00062                         kCmdResetMemory,
00063                         kCmdClose,
00064                         kCmdDumpMemory,
00065                         kCmdDumpPrediction,
00066                         kCmdGenerateDOTGraph, // params: path
00067                         kCmdGenerateDOTLocalGraph, // params: path, id, margin
00068                         kCmdGenerateTOROGraphLocal, // params: path, optimized
00069                         kCmdGenerateTOROGraphGlobal, // params: path, optimized
00070                         kCmdCleanDataBuffer,
00071                         kCmdPublish3DMapLocal, // params: optimized
00072                         kCmdPublish3DMapGlobal, // params: optimized
00073                         kCmdPublishTOROGraphGlobal, // params: optimized
00074                         kCmdPublishTOROGraphLocal, // params: optimized
00075                         kCmdTriggerNewMap,
00076                         kCmdPause,
00077                         kCmdGoal}; // params: label or location ID
00078 public:
00079         RtabmapEventCmd(Cmd cmd, const std::string & strValue = "", int intValue = 0, const ParametersMap & parameters = ParametersMap()) :
00080                         UEvent(0),
00081                         _cmd(cmd),
00082                         _strValue(strValue),
00083                         _intValue(intValue),
00084                         _parameters(parameters){}
00085 
00086         virtual ~RtabmapEventCmd() {}
00087         Cmd getCmd() const {return _cmd;}
00088 
00089         void setStr(const std::string & str) {_strValue = str;}
00090         const std::string & getStr() const {return _strValue;}
00091 
00092         void setInt(int v) {_intValue = v;}
00093         int getInt() const {return _intValue;}
00094 
00095         const ParametersMap & getParameters() const {return _parameters;}
00096 
00097         virtual std::string getClassName() const {return std::string("RtabmapEventCmd");}
00098 
00099 private:
00100         Cmd _cmd;
00101         std::string _strValue;
00102         int _intValue;
00103         ParametersMap _parameters;
00104 };
00105 
00106 class RtabmapEventInit : public UEvent
00107 {
00108 public:
00109         enum dummy {d}; // Hack, to fix Eclipse complaining about not defined Status enum ?!
00110         enum Status {
00111                 kInitializing,
00112                 kInitialized,
00113                 kClosing,
00114                 kClosed,
00115                 kInfo,
00116                 kError
00117         };
00118 
00119 public:
00120         RtabmapEventInit(Status status, const std::string & info = std::string()) :
00121                 UEvent(0),
00122                 _status(status),
00123                 _info(info)
00124         {}
00125 
00126         // for convenience
00127         RtabmapEventInit(const std::string & info) :
00128                 UEvent(0),
00129                 _status(kInfo),
00130                 _info(info)
00131         {}
00132 
00133         Status getStatus() const {return _status;}
00134         const std::string & getInfo() const {return _info;}
00135 
00136         virtual ~RtabmapEventInit() {}
00137         virtual std::string getClassName() const {return std::string("RtabmapEventInit");}
00138 private:
00139         Status _status;
00140         std::string _info; // "Loading signatures", "Loading words" ...
00141 };
00142 
00143 class RtabmapEvent3DMap : public UEvent
00144 {
00145 public:
00146         RtabmapEvent3DMap(int codeError = 0):
00147                 UEvent(codeError){}
00148         RtabmapEvent3DMap(
00149                         const std::map<int, Signature> & signatures,
00150                         const std::map<int, Transform> & poses,
00151                         const std::multimap<int, Link> & constraints,
00152                         const std::map<int, int> & mapIds,
00153                         const std::map<int, double> & stamps,
00154                         const std::map<int, std::string> & labels,
00155                         const std::map<int, std::vector<unsigned char> > & userDatas) :
00156                 UEvent(0),
00157                 _signatures(signatures),
00158                 _poses(poses),
00159                 _constraints(constraints),
00160                 _mapIds(mapIds),
00161                 _stamps(stamps),
00162                 _labels(labels),
00163                 _userDatas(userDatas)
00164         {}
00165 
00166         virtual ~RtabmapEvent3DMap() {}
00167 
00168         const std::map<int, Signature> & getSignatures() const {return _signatures;}
00169         const std::map<int, Transform> & getPoses() const {return _poses;}
00170         const std::multimap<int, Link> & getConstraints() const {return _constraints;}
00171         const std::map<int, int> & getMapIds() const {return _mapIds;}
00172         const std::map<int, double> & getStamps() const {return _stamps;}
00173         const std::map<int, std::string> & getLabels() const {return _labels;}
00174         const std::map<int, std::vector<unsigned char> > & getUserDatas() const {return _userDatas;}
00175 
00176         virtual std::string getClassName() const {return std::string("RtabmapEvent3DMap");}
00177 
00178 private:
00179         std::map<int, Signature> _signatures;
00180         std::map<int, Transform> _poses;
00181         std::multimap<int, Link> _constraints;
00182         std::map<int, int> _mapIds;
00183         std::map<int, double> _stamps;
00184         std::map<int, std::string> _labels;
00185         std::map<int, std::vector<unsigned char> > _userDatas;
00186 };
00187 
00188 class RtabmapGlobalPathEvent : public UEvent
00189 {
00190 public:
00191         RtabmapGlobalPathEvent():
00192                 UEvent(0) {}
00193         RtabmapGlobalPathEvent(int goalId, const std::vector<std::pair<int, Transform> > & poses) :
00194                 UEvent(goalId),
00195                 _poses(poses) {}
00196 
00197         virtual ~RtabmapGlobalPathEvent() {}
00198         int getGoal() const {return this->getCode();}
00199         const std::vector<std::pair<int, Transform> > & getPoses() const {return _poses;}
00200         virtual std::string getClassName() const {return std::string("RtabmapGlobalPathEvent");}
00201 
00202 private:
00203         std::vector<std::pair<int, Transform> > _poses;
00204 };
00205 
00206 } // namespace rtabmap
00207 
00208 #endif /* RTABMAPEVENT_H_ */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Fri Aug 28 2015 12:51:32