53 bool intermediateNodesIgnored,
54 bool landmarksIgnored,
59 _paths(
uSplit(databasePath,
';')),
60 _odometryIgnored(odometryIgnored),
61 _ignoreGoalDelay(ignoreGoalDelay),
62 _goalsIgnored(goalsIgnored),
65 _cameraIndex(cameraIndex),
66 _intermediateNodesIgnored(intermediateNodesIgnored),
67 _landmarksIgnored(landmarksIgnored),
68 _featuresIgnored(featuresIgnored),
69 _startMapId(startMapId),
70 _stopMapId(stopMapId),
72 _currentId(_ids.
end()),
97 bool intermediateNodesIgnored,
98 bool landmarksIgnored,
143 const std::string & calibrationFolder,
144 const std::string & cameraName)
162 UERROR(
"No database path set...");
166 std::string path =
_paths.front();
169 UERROR(
"Database path does not exist (%s)", path.c_str());
178 UERROR(
"Driver doesn't exist.");
183 UERROR(
"Can't open database %s", path.c_str());
194 if(iter ==
_ids.end())
196 UWARN(
"Start index is too high (%d), the last ID in database is %d. Starting from beginning...",
_startId, *
_ids.rbegin());
206 std::vector<CameraModel> models;
207 std::vector<StereoCameraModel> stereoModels;
212 if(models.at(0).isValidForProjection())
216 else if(models.at(0).fx() && models.at(0).fy() && models.at(0).imageWidth() == 0)
229 else if(stereoModels.size() && stereoModels.at(0).isValidForProjection())
272 UINFO(
"Last ID %d has been reached! Ignoring",
_stopId);
277 UINFO(
"no more images...");
278 while(
_paths.size() > 1 && data.
id() == 0)
281 UWARN(
"Loading next database \"%s\"...",
_paths.front().c_str());
284 UERROR(
"Failed to initialize the next database \"%s\"",
_paths.front().c_str());
297 double previousStamp = data.
stamp();
298 if(previousStamp == 0)
310 std::string goalStr = (
const char *)data.
userDataRaw().data;
313 std::list<std::string> strs =
uSplit(goalStr,
':');
316 goalId = *strs.rbegin();
328 Transform localTransform, pose, groundTruth;
329 std::vector<float> velocity;
333 if(previousStamp && stamp && stamp > previousStamp)
335 delay = stamp - previousStamp;
341 UWARN(
"Goal \"%s\" detected, posting it! Waiting %f seconds before sending next data...",
342 goalId.c_str(), delay);
346 UWARN(
"Goal \"%s\" detected, posting it!", goalId.c_str());
376 std::list<int> signIds;
378 std::list<Signature *> signatures;
380 if(signatures.empty())
389 UDEBUG(
"Ignoring node %d (intermediate nodes ignored)", s->
id());
408 cv::Mat globalPoseCov;
410 std::multimap<int, Link> priorLinks;
412 if( priorLinks.size() &&
413 !priorLinks.begin()->second.transform().isNull() &&
414 priorLinks.begin()->second.infMatrix().cols == 6 &&
415 priorLinks.begin()->second.infMatrix().rows == 6)
417 globalPose = priorLinks.begin()->second.transform();
418 globalPoseCov = priorLinks.begin()->second.infMatrix().inv();
420 globalPoseCov.at<
double>(3,3)>=9999 &&
421 globalPoseCov.at<
double>(4,4)>=9999 &&
422 globalPoseCov.at<
double>(5,5)>=9999)
430 std::multimap<int, Link> gravityLinks;
432 if( gravityLinks.size() &&
433 !gravityLinks.begin()->second.transform().isNull() &&
434 gravityLinks.begin()->second.infMatrix().cols == 6 &&
435 gravityLinks.begin()->second.infMatrix().rows == 6)
437 gravityTransform = gravityLinks.begin()->second.transform();
443 std::multimap<int, Link> landmarkLinks;
445 for(std::multimap<int, Link>::iterator iter=landmarkLinks.begin(); iter!=landmarkLinks.end(); ++iter)
447 cv::Mat landmarkSize = iter->second.uncompressUserDataConst();
448 landmarks.insert(std::make_pair(-iter->first,
450 !landmarkSize.empty() && landmarkSize.type() == CV_32FC1 && landmarkSize.total()==1?landmarkSize.at<
float>(0,0):0.0
f,
451 iter->second.transform(),
452 iter->second.infMatrix().inv())));
456 cv::Mat infMatrix = cv::Mat::eye(6,6,CV_64FC1);
459 std::multimap<int, Link> links;
461 if(links.size() && links.begin()->first < *
_currentId)
464 infMatrix = links.begin()->second.infMatrix();
473 UDEBUG(
"First node of map %d, variance set to 9999", s->
mapId());
482 infMatrix = links.begin()->second.infMatrix();
511 UERROR(
"The option to use database stamps is set (framerate<0), but there are no stamps saved in the database! Aborting...");
519 if(sleepTime > 10000)
521 UWARN(
"Detected long delay (%d sec, stamps = %f vs %f). Waiting a maximum of 10 seconds.",
582 if(!gravityTransform.
isNull())
586 cv::Vec4d(q.x(), q.y(), q.z(), q.w()), cv::Mat::eye(3,3,CV_64FC1),
587 cv::Vec3d(), cv::Mat(),
588 cv::Vec3d(), cv::Mat(),
593 UDEBUG(
"Laser=%d RGB/Left=%d Depth/Right=%d, Grid=%d, UserData=%d, GlobalPose=%d, GPS=%d, IMU=%d",
601 gravityTransform.
isNull()?0:1);
604 const std::vector<cv::KeyPoint> & keypoints = s->
getWordsKpts();
605 const std::vector<cv::Point3f> & keypoints3D = s->
getWords3();
607 !keypoints.empty() &&
608 (keypoints3D.empty() || keypoints.size() == keypoints3D.size()) &&
609 (descriptors.empty() || (int)keypoints.size() == descriptors.rows))
611 data.
setFeatures(keypoints, keypoints3D, descriptors);
613 else if(!
_featuresIgnored && !keypoints.empty() && (!keypoints3D.empty() || !descriptors.empty()))
615 UERROR(
"Missing feature data, features won't be published.");
620 UWARN(
"No image loaded from the database for id=%d!", seq);
627 UWARN(
"Reading the database: odometry is null! " 628 "Please set \"Ignore odometry = true\" if there is " 629 "no odometry in the database.");
645 UERROR(
"Not initialized...");
bool uIsInteger(const std::string &str, bool checkForSign=true)
std::list< std::string > _paths
cv::Mat _previousInfMatrix
const double & stamp() const
static void post(UEvent *event, bool async=true, const UEventsSender *sender=0)
const Transform & getGroundTruthPose() const
virtual bool init(const std::string &calibrationFolder=".", const std::string &cameraName="")
Signature * loadSignature(int id, bool *loadedFromTrash=0)
const std::vector< float > & getVelocity() const
SensorData getNextData(CameraInfo *info=0)
const LaserScan & laserScanCompressed() const
virtual bool isCalibrated() const
void setGlobalPose(const Transform &pose, const cv::Mat &covariance)
std::pair< std::string, std::string > ParametersPair
const cv::Mat & getWordsDescriptors() const
const cv::Mat & depthOrRightRaw() const
std::map< int, Landmark > Landmarks
void setRGBDImage(const cv::Mat &rgb, const cv::Mat &depth, const CameraModel &model, bool clearPreviousData=true)
std::map< std::string, std::string > ParametersMap
const std::vector< cv::Point3f > & getWords3() const
virtual std::string getSerial() const
std::vector< float > odomVelocity
Some conversion functions.
void loadLinks(int signatureId, std::multimap< int, Link > &links, Link::Type type=Link::kUndef) const
float gridCellSize() const
bool openConnection(const std::string &url, bool overwritten=false)
const std::vector< cv::KeyPoint > & getWordsKpts() const
#define UASSERT(condition)
DBReader(const std::string &databasePath, float frameRate=0.0f, bool odometryIgnored=false, bool ignoreGoalDelay=false, bool goalsIgnored=false, int startId=0, int cameraIndex=-1, int stopId=0, bool intermediateNodesIgnored=false, bool landmarksIgnored=false, bool featuresIgnored=false, int startMapId=0, int stopMapId=-1)
Wrappers of STL for convenient functions.
std::list< std::string > uSplit(const std::string &str, char separator=' ')
const std::vector< CameraModel > & cameraModels() const
bool getNodeInfo(int signatureId, Transform &pose, int &mapId, int &weight, std::string &label, double &stamp, Transform &groundTruthPose, std::vector< float > &velocity, GPS &gps, EnvSensors &sensors) const
void closeConnection(bool save=true, const std::string &outputUrl="")
const cv::Mat & imageRaw() const
bool getCalibration(int signatureId, std::vector< CameraModel > &models, std::vector< StereoCameraModel > &stereoModels) const
void getAllNodeIds(std::set< int > &ids, bool ignoreChildren=false, bool ignoreBadSignatures=false, bool ignoreIntermediateNodes=false) const
bool _intermediateNodesIgnored
void getNodeData(int signatureId, SensorData &data, bool images=true, bool scan=true, bool userData=true, bool occupancyGrid=true) const
static DBDriver * create(const ParametersMap ¶meters=ParametersMap())
float getImageRate() const
void setUserData(const cv::Mat &userData, bool clearPreviousData=true)
void uSleep(unsigned int ms)
const LaserScan & laserScanRaw() const
const cv::Mat & userDataRaw() const
SensorData & sensorData()
void loadNodeData(Signature *signature, bool images=true, bool scan=true, bool userData=true, bool occupancyGrid=true) const
void loadSignatures(const std::list< int > &ids, std::list< Signature *> &signatures, std::set< int > *loadedFromTrash=0)
const Transform & getPose() const
ULogger class and convenient macros.
void setStamp(double stamp)
void setLandmarks(const Landmarks &landmarks)
void setIMU(const IMU &imu)
std::set< int >::iterator _currentId
void setGroundTruth(const Transform &pose)
std::map< EnvSensor::Type, EnvSensor > EnvSensors
const cv::Mat & imageCompressed() const
void setFeatures(const std::vector< cv::KeyPoint > &keypoints, const std::vector< cv::Point3f > &keypoints3D, const cv::Mat &descriptors)
virtual SensorData captureImage(CameraInfo *info=0)
const std::multimap< int, int > & getWords() const