47 _dataBufferMaxSize(
Parameters::defaultRtabmapImageBufferSize()),
48 _rate(
Parameters::defaultRtabmapDetectionRate()),
49 _createIntermediateNodes(
Parameters::defaultRtabmapCreateIntermediateNodes()),
50 _frameRateTimer(new
UTimer()),
131 UDEBUG(
"optimized=%s, full=%s, graphOnly=%s", optimized?
"true":
"false", full?
"true":
"false", graphOnly?
"true":
"false");
134 std::map<int, Signature> signatures;
135 std::map<int, Transform> poses;
136 std::multimap<int, Link> constraints;
137 std::map<int, int> mapIds;
138 std::map<int, double> stamps;
139 std::map<int, std::string> labels;
140 std::map<int, std::vector<unsigned char> > userDatas;
159 UERROR(
"Rtabmap is null!");
168 UERROR(
"Cannot start rtabmap thread if no rtabmap object is set! Stopping the thread...");
207 UASSERT(!parameters.at(
"RtabmapThread/DatabasePath").empty());
208 str = parameters.at(
"RtabmapThread/DatabasePath");
209 parameters.erase(
"RtabmapThread/DatabasePath");
230 UWARN(
"Closing... %d data still buffered! They will be cleared.", (
int)
_dataBuffer.size());
243 parameters.at(
"path"),
244 atoi(parameters.at(
"id").c_str()),
245 atoi(parameters.at(
"margin").c_str()));
249 parameters.at(
"path"),
252 atoi(parameters.at(
"type").c_str()));
267 id = atoi(parameters.at(
"id").c_str());
273 UERROR(
"Failed to find a node with label \"%s\".", parameters.at(
"label").c_str());
278 UERROR(
"Failed to set a goal. ID (%d) should be positive > 0",
id);
283 UERROR(
"Failed to compute a path to goal %d.",
id);
287 parameters.at(
"label"),
301 UFATAL(
"Invalid state !?!?");
316 else if(event->
getClassName().compare(
"CameraEvent") == 0)
355 else if(event->
getClassName().compare(
"OdometryEvent") == 0)
368 else if(event->
getClassName().compare(
"UserDataEvent") == 0)
373 bool updated =
false;
376 if(!e->
data().empty())
384 UWARN(
"New user data received before the last one was processed... replacing " 385 "user data with this new one. Note that UserDataEvent should be used only " 386 "if the rate of UserDataEvent is lower than RTAB-Map's detection rate (%f Hz).",
_rate);
390 else if(event->
getClassName().compare(
"RtabmapEventCmd") == 0)
507 UWARN(
"Cmd %d unknown!", cmd);
510 else if(event->
getClassName().compare(
"ParamEvent") == 0)
546 UERROR(
"RTAB-Map is not initialized! Ignoring received data...");
557 bool ignoreFrame =
false;
572 UWARN(
"Odometry is reset (identity pose detected). Increment map id! (stamp=%fs)", odomEvent.
data().
stamp());
576 UWARN(
"Odometry is reset (high variance (%f >=9999 detected, stamp=%fs). Increment map id!", odomEvent.
info().
reg.
covariance.at<
double>(0,0), odomEvent.
data().
stamp());
597 else if(!ignoreFrame)
618 tmp.
setFeatures(std::vector<cv::KeyPoint>(), std::vector<cv::Point3f>(), cv::Mat());
632 ULOGGER_WARN(
"Data buffer is full, the oldest data is removed to add the new one.");
653 bool dataFilled =
false;
654 bool triggerNewMap =
false;
675 triggerNewMap =
true;
const UVariant & value2() const
static bool parse(const ParametersMap ¶meters, const std::string &key, bool &value)
std::list< OdometryEvent > _dataBuffer
void clearPath(int status)
bool _createIntermediateNodes
void exportPoses(const std::string &path, bool optimized, bool global, int format)
#define ULOGGER_INFO(...)
bool computePath(int targetNode, bool global)
const UVariant & value3() const
std::pair< std::string, std::string > ParametersPair
void generateDOTGraph(const std::string &path, int id=0, int margin=5)
bool UTILITE_EXP uStr2Bool(const char *str)
bool labelLocation(int id, const std::string &label)
OdometryInfo copyWithoutData() const
unsigned int _dataBufferMaxSize
GLM_FUNC_DECL genType e()
std::map< std::string, std::string > ParametersMap
std::string UTILITE_EXP uBool2Str(bool boolean)
const UVariant & value1() const
void init(const ParametersMap ¶meters, const std::string &databasePath="", bool loadDatabaseParameters=false)
std::vector< float > odomVelocity
Some conversion functions.
bool acquire(int n=1, int ms=0)
void post(UEvent *event, bool async=true) const
void getGraph(std::map< int, Transform > &poses, std::multimap< int, Link > &constraints, bool optimized, bool global, std::map< int, Signature > *signatures=0, bool withImages=false, bool withScan=false, bool withUserData=false, bool withGrid=false, bool withWords=true, bool withGlobalDescriptors=true) const
virtual void mainLoopBegin()
bool uIsFinite(const T &value)
#define UASSERT(condition)
Wrappers of STL for convenient functions.
const cv::Mat & data() const
const Transform & pose() const
void close(bool databaseSaved=true, const std::string &ouputDatabasePath="")
#define ULOGGER_DEBUG(...)
virtual std::string getClassName() const =0
void publishMap(bool optimized, bool full, bool graphOnly) const
bool getData(OdometryEvent &data)
int getSignatureIdByLabel(const std::string &label, bool lookInDatabase=true) const
const Statistics & getStatistics() const
static void registerCurrentThread(const std::string &name)
bool process(const SensorData &data, Transform odomPose, const cv::Mat &odomCovariance=cv::Mat::eye(6, 6, CV_64FC1), const std::vector< float > &odomVelocity=std::vector< float >(), const std::map< std::string, float > &externalStats=std::map< std::string, float >())
Main loop of rtabmap.
virtual void mainLoopKill()
const UVariant & value4() const
const OdometryInfo & info() const
RecoveryProgressState state
void parseParameters(const ParametersMap ¶meters)
const cv::Mat & covariance() const
void setUserData(const cv::Mat &userData, bool clearPreviousData=true)
void setDetectorRate(float rate)
int getPathStatus() const
const CameraInfo & info() const
const std::vector< std::pair< int, Transform > > & getPath() const
void setDataBufferSize(unsigned int bufferSize)
#define ULOGGER_WARN(...)
void dumpPrediction() const
ULogger class and convenient macros.
const Memory * getMemory() const
void close(bool databaseSaved, const std::string &databasePath="")
std::string toStr(bool *ok=0) const
void addData(const OdometryEvent &odomEvent)
void createIntermediateNodes(bool enabled)
virtual bool handleEvent(UEvent *anEvent)
std::queue< ParametersMap > _stateParam
const SensorData & data() const
std::vector< float > velocity() const
bool isIncremental() const
static void removeHandler(UEventsHandler *handler)
void join(bool killFirst=false)
std::list< double > _newMapEvents
void pushNewState(State newState, const ParametersMap ¶meters=ParametersMap())
RtabmapThread(Rtabmap *rtabmap)
void setFeatures(const std::vector< cv::KeyPoint > &keypoints, const std::vector< cv::Point3f > &keypoints3D, const cv::Mat &descriptors)
void addStatistic(const std::string &name, float value)
std::queue< State > _state