MRPT  2.0.1
test.cpp
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2020, Individual contributors, see AUTHORS file |
6  | See: https://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See: https://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
10 /* ------------------------------------------------------
11  rgbd2rawlog
12  A small tool to translate RGB+D datasets from TUM:
13  http://cvpr.in.tum.de/data/datasets/rgbd-dataset/
14 
15  into MRPT rawlog binary format, ready to be parsed
16  by RawLogViewer or user programs.
17 
18 Usage:
19  rgbd_dataset2rawlog [PATH_TO_RGBD_DATASET] [OUTPUT_NAME]
20 
21 Where expected input files are:
22  - PATH_TO_RGBD_DATASET/accelerometer.txt
23  - PATH_TO_RGBD_DATASET/depth.txt
24  - PATH_TO_RGBD_DATASET/rgb.txt
25  - PATH_TO_RGBD_DATASET/rgb/... (Images, 3x8u)
26  - PATH_TO_RGBD_DATASET/depth/... (Images, 1x16u)
27 
28 Output files:
29  - OUTPUT_NAME.rawlog: The output rawlog file.
30  - OUTPUT_NAME_Images/...: External RGB images.
31 
32  ------------------------------------------------------ */
33 
39 #include <mrpt/system/filesystem.h>
40 #include <iostream>
41 
42 using namespace std;
43 using namespace mrpt;
44 using namespace mrpt::obs;
45 using namespace mrpt::serialization;
46 
47 const double KINECT_FPS = 30.0;
48 
49 // Based on:
50 // http://stackoverflow.com/questions/218488/finding-best-matching-key-for-a-given-key-in-a-sorted-stl-container
51 template <class CONTAINER>
52 typename CONTAINER::const_iterator find_closest(
53  const CONTAINER& data, const typename CONTAINER::key_type& searchkey)
54 {
55  typename CONTAINER::const_iterator upper = data.lower_bound(searchkey);
56  if (upper == data.begin() || upper->first == searchkey) return upper;
57  typename CONTAINER::const_iterator lower = upper;
58  --lower;
59  if (upper == data.end() ||
60  (searchkey - lower->first) < (upper->first - searchkey))
61  return lower;
62  return upper;
63 }
64 
65 void rgbd2rawlog(const string& src_path, const string& out_name)
66 {
67  const string in_fil_acc = src_path + string("/accelerometer.txt");
68  const string in_fil_depth =
69  mrpt::system::fileExists(src_path + string("/ir.txt"))
70  ? src_path + string("/ir.txt")
71  : src_path + string("/depth.txt");
72  const string in_fil_rgb = src_path + string("/rgb.txt");
73 
74  // ASSERT_FILE_EXISTS_(in_fil_acc)
75  // ASSERT_FILE_EXISTS_(in_fil_depth)
76  // ASSERT_FILE_EXISTS_(in_fil_rgb)
77 
78  // make a list with RGB & DEPTH files ------------------------
79  map<double, string> list_rgb, list_depth;
80  map<double, vector<double>> list_acc;
81  std::istringstream line;
82  if (mrpt::system::fileExists(in_fil_rgb))
83  {
84  mrpt::io::CTextFileLinesParser fparser(in_fil_rgb);
85  while (fparser.getNextLine(line))
86  {
87  double tim;
88  string f;
89  if (line >> tim >> f) list_rgb[tim] = f;
90  }
91  }
92  if (mrpt::system::fileExists(in_fil_depth))
93  {
94  mrpt::io::CTextFileLinesParser fparser(in_fil_depth);
95  while (fparser.getNextLine(line))
96  {
97  double tim;
98  string f;
99  if (line >> tim >> f) list_depth[tim] = f;
100  }
101  }
102  if (mrpt::system::fileExists(in_fil_acc))
103  {
104  mrpt::io::CTextFileLinesParser fparser(in_fil_acc);
105  while (fparser.getNextLine(line))
106  {
107  double tim;
108  double ax, ay, az;
109  if (line >> tim >> ax >> ay >> az)
110  {
111  vector<double>& v = list_acc[tim];
112  v.resize(3);
113  v[0] = ax;
114  v[1] = ay;
115  v[2] = az;
116  }
117  }
118  }
119  cout << "Parsed: " << list_depth.size() << " / " << list_rgb.size() << " / "
120  << list_acc.size() << " depth/rgb/acc entries.\n";
121 
122  const bool only_ir = list_depth.size() > 10 && list_rgb.empty();
123  const bool only_rgb = list_depth.empty() && list_rgb.size() > 10;
124 
125  // Create output directory for images ------------------------------
126  const string out_img_dir = out_name + string("_Images");
127 
128  cout << "Creating images directory: " << out_img_dir << endl;
129  mrpt::system::createDirectory(out_img_dir);
130 
131  // Create rawlog file ----------------------------------------------
132  const string out_rawlog_fil = out_name + string(".rawlog");
133  cout << "Creating rawlog: " << out_rawlog_fil << endl;
134  mrpt::io::CFileGZOutputStream f_out(out_rawlog_fil);
135 
136  // Fill out the common field to all entries:
138  obs.sensorLabel = "KINECT";
139  obs.range_is_depth = true; // Kinect style: ranges are actually depth
140  // values, not Euclidean distances.
141 
142  // Range & RGB images are already registered and warped to remove
143  // distortion:
144  const double FOCAL = 525.0;
145  obs.cameraParams.nrows = 640;
146  obs.cameraParams.ncols = 480;
147  obs.cameraParams.fx(FOCAL);
148  obs.cameraParams.fy(FOCAL);
149  obs.cameraParams.cx(319.5);
150  obs.cameraParams.cy(239.5);
153  0, 0, 0, mrpt::DEG2RAD(-90), 0,
154  mrpt::DEG2RAD(-90)); // No translation between rgb & range
155  // cameras, and rotation only due to XYZ
156  // axes conventions.
157 
158  CObservationIMU obs_imu;
159  obs_imu.sensorLabel = "KINECT_ACC";
160  obs_imu.dataIsPresent[IMU_X_ACC] = true;
161  obs_imu.dataIsPresent[IMU_Y_ACC] = true;
162  obs_imu.dataIsPresent[IMU_Z_ACC] = true;
163 
164  // Go thru the data:
165  unsigned int counter = 0;
166  if (!only_ir && !only_rgb)
167  {
168  for (map<double, string>::const_iterator it_list_rgb = list_rgb.begin();
169  it_list_rgb != list_rgb.end(); ++it_list_rgb)
170  {
171  cout << "Processing image " << counter << "\r";
172  cout.flush();
173  counter++;
174 
175  // This is not the most efficient solution in the world, but...come
176  // on! it's just a rawlog converter tool!
177  map<double, string>::const_iterator it_list_depth =
178  find_closest(list_depth, it_list_rgb->first);
179 
180  const double At =
181  std::abs(it_list_rgb->first - it_list_depth->first);
182  if (At > (1. / KINECT_FPS) * .5)
183  {
184  cout << "\nWarning: Discarding observation for too separated "
185  "RGB/D timestamps: "
186  << At * 1e3 << " ms\n";
187  }
188  else
189  {
190  // OK, we accept this RGB-DEPTH pair:
191  const double avrg_time =
192  .5 * (it_list_rgb->first + it_list_depth->first);
194 
195  // RGB img:
196  obs.hasIntensityImage = true;
198  src_path + string("/") + it_list_rgb->second);
199  const string sRGBfile =
200  mrpt::format("%.06f_rgb.png", avrg_time);
202  out_img_dir + string("/") + sRGBfile);
203  obs.intensityImage.setExternalStorage(sRGBfile);
204 
205  // Depth:
206  obs.hasRangeImage = true;
208  mrpt::img::CImage depth_img;
209  if (!depth_img.loadFromFile(
210  src_path + string("/") + it_list_depth->second))
211  throw std::runtime_error(
212  string("Error loading depth image!: ") +
213  it_list_depth->second);
214 
215  const unsigned int w = depth_img.getWidth();
216  const unsigned int h = depth_img.getHeight();
217  obs.rangeImage_setSize(h, w);
218 
219  for (unsigned int row = 0; row < h; row++)
220  {
221  const uint16_t* ptr = depth_img.ptrLine<uint16_t>(row);
222  for (unsigned int col = 0; col < w; col++)
223  obs.rangeImage(row, col) = (*ptr++) * (1.f / 5000);
224  }
225 
226  const string sDepthfile =
227  mrpt::format("%.06f_depth.bin", avrg_time);
229  sDepthfile, out_img_dir + string("/"));
230 
231  // save:
232  archiveFrom(f_out) << obs;
233 
234  // Search for acc data:
235  map<double, vector<double>>::const_iterator it_list_acc =
236  find_closest(list_acc, avrg_time);
237  const double At_acc =
238  std::abs(it_list_rgb->first - it_list_acc->first);
239  if (At_acc < 1e-2)
240  {
241  obs_imu.timestamp =
243 
244  obs_imu.rawMeasurements[IMU_X_ACC] = it_list_acc->second[0];
245  obs_imu.rawMeasurements[IMU_Y_ACC] = it_list_acc->second[1];
246  obs_imu.rawMeasurements[IMU_Z_ACC] = it_list_acc->second[2];
247 
248  archiveFrom(f_out) << obs_imu;
249  }
250  }
251  }
252  }
253  else if (only_ir)
254  {
255  for (map<double, string>::const_iterator it_list_depth =
256  list_depth.begin();
257  it_list_depth != list_depth.end(); ++it_list_depth)
258  {
259  cout << "Processing image " << counter << "\r";
260  cout.flush();
261  counter++;
262 
263  const double avrg_time = it_list_depth->first;
264  obs.timestamp =
265  mrpt::system::time_tToTimestamp(it_list_depth->first);
266 
267  // Depth:
268  obs.hasRangeImage = true;
270  mrpt::img::CImage depth_img;
271  if (!depth_img.loadFromFile(
272  src_path + string("/") + it_list_depth->second))
273  throw std::runtime_error(
274  string("Error loading depth image!: ") +
275  it_list_depth->second);
276 
277  const unsigned int w = depth_img.getWidth();
278  const unsigned int h = depth_img.getHeight();
279  obs.rangeImage_setSize(h, w);
280 
281  for (unsigned int row = 0; row < h; row++)
282  {
283  const uint16_t* ptr = depth_img.ptrLine<uint16_t>(row);
284  for (unsigned int col = 0; col < w; col++)
285  obs.rangeImage(row, col) = (*ptr++) * (1.f / 5000);
286  }
287 
288  const string sDepthfile =
289  mrpt::format("%.06f_depth.bin", avrg_time);
291  sDepthfile, out_img_dir + string("/"));
292 
293  // save:
294  archiveFrom(f_out) << obs;
295  }
296  }
297  else if (only_rgb)
298  {
299  for (map<double, string>::const_iterator it_list_rgb = list_rgb.begin();
300  it_list_rgb != list_rgb.end(); ++it_list_rgb)
301  {
302  cout << "Processing image " << counter << "\r";
303  cout.flush();
304  counter++;
305 
306  const double avrg_time = it_list_rgb->first;
307  obs.timestamp = mrpt::system::time_tToTimestamp(it_list_rgb->first);
308 
309  // RGB img:
310  obs.hasIntensityImage = true;
312  src_path + string("/") + it_list_rgb->second);
313  const string sRGBfile = mrpt::format("%.06f_rgb.png", avrg_time);
314  obs.intensityImage.saveToFile(out_img_dir + string("/") + sRGBfile);
315  obs.intensityImage.setExternalStorage(sRGBfile);
316 
317  // save:
318  archiveFrom(f_out) << obs;
319  }
320  }
321 
322  cout << "\nAll done!\n";
323 }
324 
325 // ------------------------------------------------------
326 // MAIN
327 // ------------------------------------------------------
328 int main(int argc, char** argv)
329 {
330  try
331  {
332  if (argc != 3)
333  {
334  cerr << "Usage: " << argv[0]
335  << " [PATH_TO_RGBD_DATASET] [OUTPUT_NAME]\n";
336  return 1;
337  }
338 
339  rgbd2rawlog(argv[1], argv[2]);
340 
341  return 0;
342  }
343  catch (const std::exception& e)
344  {
345  std::cerr << "MRPT error: " << mrpt::exception_to_str(e) << std::endl;
346  return -1;
347  }
348  catch (...)
349  {
350  printf("Untyped exception!!");
351  return -1;
352  }
353 }
uint32_t nrows
Definition: TCamera.h:40
mrpt::img::TCamera cameraParams
Projection parameters of the depth camera.
bool createDirectory(const std::string &dirName)
Creates a directory.
Definition: filesystem.cpp:161
std::vector< bool > dataIsPresent
Each entry in this vector is true if the corresponding data index contains valid data (the IMU unit s...
std::vector< double > rawMeasurements
The accelerometer and/or gyroscope measurements taken by the IMU at the given timestamp.
double fx() const
Get the value of the focal length x-value (in pixels).
Definition: TCamera.h:175
std::string std::string format(std::string_view fmt, ARGS &&... args)
Definition: format.h:26
const T * ptrLine(unsigned int row) const
Returns a pointer to the first pixel of the given line.
Definition: img/CImage.h:597
bool fileExists(const std::string &fileName)
Test if a given file (or directory) exists.
Definition: filesystem.cpp:128
double fy() const
Get the value of the focal length y-value (in pixels).
Definition: TCamera.h:177
A range or depth 3D scan measurement, as from a time-of-flight range camera or a structured-light dep...
A class for parsing text files, returning each non-empty and non-comment line, along its line number...
size_t getHeight() const override
Returns the height of the image in pixels.
Definition: CImage.cpp:849
void setExternalStorage(const std::string &fileName) noexcept
By using this method the image is marked as referenced to an external file, which will be loaded only...
Definition: CImage.cpp:1571
y-axis acceleration (local/vehicle frame) (m/sec2)
STL namespace.
This class stores measurements from an Inertial Measurement Unit (IMU) (attitude estimation, raw gyroscope and accelerometer values), altimeters or magnetometers.
z-axis acceleration (local/vehicle frame) (m/sec2)
int counter
void rangeImage_convertToExternalStorage(const std::string &fileName, const std::string &use_this_base_dir)
Users won&#39;t normally want to call this, it&#39;s only used from internal MRPT programs.
CArchiveStreamBase< STREAM > archiveFrom(STREAM &s)
Helper function to create a templatized wrapper CArchive object for a: MRPT&#39;s CStream, std::istream, std::ostream, std::stringstream.
Definition: CArchive.h:592
const double KINECT_FPS
bool loadFromFile(const std::string &fileName, int isColor=-1)
Load image from a file, whose format is determined from the extension (internally uses OpenCV)...
Definition: CImage.cpp:305
size_t getWidth() const override
Returns the width of the image in pixels.
Definition: CImage.cpp:818
mrpt::poses::CPose3D relativePoseIntensityWRTDepth
Relative pose of the intensity camera wrt the depth camera (which is the coordinates origin for this ...
double cy() const
Get the value of the principal point y-coordinate (in pixels).
Definition: TCamera.h:173
constexpr double DEG2RAD(const double x)
Degrees to radians.
mrpt::img::CImage intensityImage
If hasIntensityImage=true, a color or gray-level intensity image of the same size than "rangeImage"...
CONTAINER::const_iterator find_closest(const CONTAINER &data, const typename CONTAINER::key_type &searchkey)
This namespace contains representation of robot actions and observations.
bool hasRangeImage
true means the field rangeImage contains valid data
mrpt::math::CMatrix_u16 rangeImage
If hasRangeImage=true, a matrix of floats with the range data as captured by the camera (in meters)...
void rangeImage_forceResetExternalStorage()
Forces marking this observation as non-externally stored - it doesn&#39;t anything else apart from reseti...
void rgbd2rawlog(const string &src_path, const string &out_name)
double cx() const
Get the value of the principal point x-coordinate (in pixels).
Definition: TCamera.h:171
std::string sensorLabel
An arbitrary label that can be used to identify the sensor.
Definition: CObservation.h:62
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
const char * argv[]
mrpt::system::TTimeStamp timestamp
The associated UTC time-stamp.
Definition: CObservation.h:60
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:85
bool hasIntensityImage
true means the field intensityImage contains valid data
void rangeImage_setSize(const int HEIGHT, const int WIDTH)
Similar to calling "rangeImage.setSize(H,W)" but this method provides memory pooling to speed-up the ...
std::string exception_to_str(const std::exception &e)
Builds a nice textual representation of a nested exception, which if generated using MRPT macros (THR...
Definition: exceptions.cpp:59
const int argc
bool saveToFile(const std::string &fileName, int jpeg_quality=95) const
Save the image to a file, whose format is determined from the extension (internally uses OpenCV)...
Definition: CImage.cpp:330
Saves data to a file and transparently compress the data using the given compression level...
mrpt::img::TCamera cameraParamsIntensity
Projection parameters of the intensity (graylevel or RGB) camera.
mrpt::system::TTimeStamp time_tToTimestamp(const double t)
Transform from standard "time_t" (actually a double number, it can contain fractions of seconds) to T...
Definition: datetime.h:91
bool range_is_depth
true: Kinect-like ranges: entries of rangeImage are distances along the +X axis; false: Ranges in ran...
x-axis acceleration (local/vehicle frame) (m/sec2)
uint32_t ncols
Camera resolution.
Definition: TCamera.h:40
A class for storing images as grayscale or RGB bitmaps.
Definition: img/CImage.h:148
static struct FontData data
Definition: gltext.cpp:144



Page generated by Doxygen 1.8.14 for MRPT 2.0.1 Git: 0fef1a6d7 Fri Apr 3 23:00:21 2020 +0200 at vie abr 3 23:20:28 CEST 2020