54 _paths(
uSplit(databasePath,
';')),
55 _odometryIgnored(odometryIgnored),
56 _ignoreGoalDelay(ignoreGoalDelay),
57 _goalsIgnored(goalsIgnored),
60 _cameraIndex(cameraIndex),
62 _currentId(_ids.end()),
113 const std::string & calibrationFolder,
114 const std::string & cameraName)
132 UERROR(
"No database path set...");
136 std::string path =
_paths.front();
139 UERROR(
"Database path does not exist (%s)", path.c_str());
148 UERROR(
"Driver doesn't exist.");
153 UERROR(
"Can't open database %s", path.c_str());
164 if(iter ==
_ids.end())
166 UWARN(
"Start index is too high (%d), the last ID in database is %d. Starting from beginning...",
_startId, *
_ids.rbegin());
176 std::vector<CameraModel> models;
182 if(models.at(0).isValidForProjection())
186 else if(models.at(0).fx() && models.at(0).fy() && models.at(0).imageWidth() == 0)
230 UINFO(
"Last ID %d has been reached! Ignoring",
_stopId);
235 UINFO(
"no more images...");
236 while(
_paths.size() > 1 && data.
id() == 0)
239 UWARN(
"Loading next database \"%s\"...",
_paths.front().c_str());
242 UERROR(
"Failed to initialize the next database \"%s\"",
_paths.front().c_str());
255 double previousStamp = data.
stamp();
256 if(previousStamp == 0)
268 std::string goalStr = (
const char *)data.
userDataRaw().data;
271 std::list<std::string> strs =
uSplit(goalStr,
':');
274 goalId = *strs.rbegin();
286 Transform localTransform, pose, groundTruth;
287 std::vector<float> velocity;
291 if(previousStamp && stamp && stamp > previousStamp)
293 delay = stamp - previousStamp;
299 UWARN(
"Goal \"%s\" detected, posting it! Waiting %f seconds before sending next data...",
300 goalId.c_str(), delay);
304 UWARN(
"Goal \"%s\" detected, posting it!", goalId.c_str());
334 std::list<int> signIds;
336 std::list<Signature *> signatures;
338 if(signatures.empty())
349 cv::Mat globalPoseCov;
351 std::multimap<int, Link> priorLinks;
353 if( priorLinks.size() &&
354 !priorLinks.begin()->second.transform().isNull() &&
355 priorLinks.begin()->second.infMatrix().cols == 6 &&
356 priorLinks.begin()->second.infMatrix().rows == 6)
358 globalPose = priorLinks.begin()->second.transform();
359 globalPoseCov = priorLinks.begin()->second.infMatrix().inv();
361 globalPoseCov.at<
double>(3,3)>=9999 &&
362 globalPoseCov.at<
double>(4,4)>=9999 &&
363 globalPoseCov.at<
double>(5,5)>=9999)
371 std::multimap<int, Link> gravityLinks;
373 if( gravityLinks.size() &&
374 !gravityLinks.begin()->second.transform().isNull() &&
375 gravityLinks.begin()->second.infMatrix().cols == 6 &&
376 gravityLinks.begin()->second.infMatrix().rows == 6)
378 gravityTransform = gravityLinks.begin()->second.transform();
381 cv::Mat infMatrix = cv::Mat::eye(6,6,CV_64FC1);
384 std::multimap<int, Link> links;
386 if(links.size() && links.begin()->first < *
_currentId)
389 infMatrix = links.begin()->second.infMatrix();
396 UDEBUG(
"First node of map %d, variance set to 9999", s->
mapId());
422 UERROR(
"The option to use database stamps is set (framerate<0), but there are no stamps saved in the database! Aborting...");
430 if(sleepTime > 10000)
432 UWARN(
"Detected long delay (%d sec, stamps = %f vs %f). Waiting a maximum of 10 seconds.",
493 if(!gravityTransform.
isNull())
497 cv::Vec4d(q.x(), q.y(), q.z(), q.w()), cv::Mat::eye(3,3,CV_64FC1),
498 cv::Vec3d(), cv::Mat(),
499 cv::Vec3d(), cv::Mat(),
503 UDEBUG(
"Laser=%d RGB/Left=%d Depth/Right=%d, Grid=%d, UserData=%d, GlobalPose=%d, GPS=%d, IMU=%d",
511 gravityTransform.
isNull()?0:1);
514 const std::vector<cv::KeyPoint> & keypoints = s->
getWordsKpts();
515 const std::vector<cv::Point3f> & keypoints3D = s->
getWords3();
516 if(!keypoints.empty() &&
517 (keypoints3D.empty() || keypoints.size() == keypoints3D.size()) &&
518 (descriptors.empty() || (int)keypoints.size() == descriptors.rows))
520 data.
setFeatures(keypoints, keypoints3D, descriptors);
522 else if(!keypoints.empty() && (!keypoints3D.empty() || !descriptors.empty()))
524 UERROR(
"Missing feature data, features won't be published.");
529 UWARN(
"No image loaded from the database for id=%d!", seq);
536 UWARN(
"Reading the database: odometry is null! " 537 "Please set \"Ignore odometry = true\" if there is " 538 "no odometry in the database.");
553 UERROR(
"Not initialized...");
bool uIsInteger(const std::string &str, bool checkForSign=true)
std::list< std::string > _paths
cv::Mat _previousInfMatrix
static void post(UEvent *event, bool async=true, const UEventsSender *sender=0)
virtual bool init(const std::string &calibrationFolder=".", const std::string &cameraName="")
const Transform & getGroundTruthPose() const
SensorData getNextData(CameraInfo *info=0)
const std::vector< float > & getVelocity() const
void getAllNodeIds(std::set< int > &ids, bool ignoreChildren=false, bool ignoreBadSignatures=false) const
void setGlobalPose(const Transform &pose, const cv::Mat &covariance)
std::pair< std::string, std::string > ParametersPair
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)
void setRGBDImage(const cv::Mat &rgb, const cv::Mat &depth, const CameraModel &model, bool clearPreviousData=true)
void getNodeData(int signatureId, SensorData &data, bool images=true, bool scan=true, bool userData=true, bool occupancyGrid=true) const
std::map< std::string, std::string > ParametersMap
float gridCellSize() const
std::vector< float > odomVelocity
Some conversion functions.
const LaserScan & laserScanRaw() const
void loadLinks(int signatureId, std::multimap< int, Link > &links, Link::Type type=Link::kUndef) const
const cv::Mat & imageRaw() const
const std::vector< cv::KeyPoint > & getWordsKpts() const
std::list< std::string > uSplit(const std::string &str, char separator= ' ')
bool openConnection(const std::string &url, bool overwritten=false)
#define UASSERT(condition)
Wrappers of STL for convenient functions.
bool isValidForProjection() const
void closeConnection(bool save=true, const std::string &outputUrl="")
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)
bool getCalibration(int signatureId, std::vector< CameraModel > &models, StereoCameraModel &stereoModel) const
const cv::Mat & getWordsDescriptors() const
const cv::Mat & depthOrRightRaw() const
const cv::Mat & userDataRaw() const
static DBDriver * create(const ParametersMap ¶meters=ParametersMap())
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 setUserData(const cv::Mat &userData, bool clearPreviousData=true)
void uSleep(unsigned int ms)
float getImageRate() const
const std::vector< CameraModel > & cameraModels() const
const Transform & getPose() const
const std::vector< cv::Point3f > & getWords3() const
SensorData & sensorData()
virtual bool isCalibrated() const
ULogger class and convenient macros.
void setStamp(double stamp)
const cv::Mat & imageCompressed() const
void setIMU(const IMU &imu)
std::set< int >::iterator _currentId
void setGroundTruth(const Transform &pose)
std::map< EnvSensor::Type, EnvSensor > EnvSensors
void setFeatures(const std::vector< cv::KeyPoint > &keypoints, const std::vector< cv::Point3f > &keypoints3D, const cv::Mat &descriptors)
virtual SensorData captureImage(CameraInfo *info=0)
virtual std::string getSerial() const
const double & stamp() const