51 template <
class CONTAINER>
53 const CONTAINER&
data,
const typename CONTAINER::key_type& searchkey)
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;
59 if (upper ==
data.end() ||
60 (searchkey - lower->first) < (upper->first - searchkey))
65 void rgbd2rawlog(
const string& src_path,
const string& out_name)
67 const string in_fil_acc = src_path + string(
"/accelerometer.txt");
68 const string in_fil_depth =
70 ? src_path + string(
"/ir.txt")
71 : src_path + string(
"/depth.txt");
72 const string in_fil_rgb = src_path + string(
"/rgb.txt");
79 map<double, string> list_rgb, list_depth;
80 map<double, vector<double>> list_acc;
81 std::istringstream line;
85 while (fparser.getNextLine(line))
89 if (line >> tim >> f) list_rgb[tim] = f;
95 while (fparser.getNextLine(line))
99 if (line >> tim >> f) list_depth[tim] = f;
105 while (fparser.getNextLine(line))
109 if (line >> tim >> ax >> ay >> az)
111 vector<double>& v = list_acc[tim];
119 cout <<
"Parsed: " << list_depth.size() <<
" / " << list_rgb.size() <<
" / " 120 << list_acc.size() <<
" depth/rgb/acc entries.\n";
122 const bool only_ir = list_depth.size() > 10 && list_rgb.empty();
123 const bool only_rgb = list_depth.empty() && list_rgb.size() > 10;
126 const string out_img_dir = out_name + string(
"_Images");
128 cout <<
"Creating images directory: " << out_img_dir << endl;
132 const string out_rawlog_fil = out_name + string(
".rawlog");
133 cout <<
"Creating rawlog: " << out_rawlog_fil << endl;
144 const double FOCAL = 525.0;
166 if (!only_ir && !only_rgb)
168 for (map<double, string>::const_iterator it_list_rgb = list_rgb.begin();
169 it_list_rgb != list_rgb.end(); ++it_list_rgb)
171 cout <<
"Processing image " <<
counter <<
"\r";
177 map<double, string>::const_iterator it_list_depth =
181 std::abs(it_list_rgb->first - it_list_depth->first);
184 cout <<
"\nWarning: Discarding observation for too separated " 186 << At * 1e3 <<
" ms\n";
191 const double avrg_time =
192 .5 * (it_list_rgb->first + it_list_depth->first);
198 src_path +
string(
"/") + it_list_rgb->second);
199 const string sRGBfile =
202 out_img_dir +
string(
"/") + sRGBfile);
210 src_path +
string(
"/") + it_list_depth->second))
211 throw std::runtime_error(
212 string(
"Error loading depth image!: ") +
213 it_list_depth->second);
215 const unsigned int w = depth_img.
getWidth();
216 const unsigned int h = depth_img.
getHeight();
219 for (
unsigned int row = 0; row < h; row++)
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);
226 const string sDepthfile =
229 sDepthfile, out_img_dir +
string(
"/"));
235 map<double, vector<double>>::const_iterator it_list_acc =
237 const double At_acc =
238 std::abs(it_list_rgb->first - it_list_acc->first);
255 for (map<double, string>::const_iterator it_list_depth =
257 it_list_depth != list_depth.end(); ++it_list_depth)
259 cout <<
"Processing image " <<
counter <<
"\r";
263 const double avrg_time = it_list_depth->first;
272 src_path +
string(
"/") + it_list_depth->second))
273 throw std::runtime_error(
274 string(
"Error loading depth image!: ") +
275 it_list_depth->second);
277 const unsigned int w = depth_img.
getWidth();
278 const unsigned int h = depth_img.
getHeight();
281 for (
unsigned int row = 0; row < h; row++)
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);
288 const string sDepthfile =
291 sDepthfile, out_img_dir +
string(
"/"));
299 for (map<double, string>::const_iterator it_list_rgb = list_rgb.begin();
300 it_list_rgb != list_rgb.end(); ++it_list_rgb)
302 cout <<
"Processing image " <<
counter <<
"\r";
306 const double avrg_time = it_list_rgb->first;
312 src_path +
string(
"/") + it_list_rgb->second);
313 const string sRGBfile =
mrpt::format(
"%.06f_rgb.png", avrg_time);
322 cout <<
"\nAll done!\n";
334 cerr <<
"Usage: " <<
argv[0]
335 <<
" [PATH_TO_RGBD_DATASET] [OUTPUT_NAME]\n";
343 catch (
const std::exception& e)
350 printf(
"Untyped exception!!");
mrpt::img::TCamera cameraParams
Projection parameters of the depth camera.
bool createDirectory(const std::string &dirName)
Creates a directory.
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).
std::string std::string format(std::string_view fmt, ARGS &&... args)
const T * ptrLine(unsigned int row) const
Returns a pointer to the first pixel of the given line.
bool fileExists(const std::string &fileName)
Test if a given file (or directory) exists.
double fy() const
Get the value of the focal length y-value (in pixels).
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.
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...
y-axis acceleration (local/vehicle frame) (m/sec2)
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)
void rangeImage_convertToExternalStorage(const std::string &fileName, const std::string &use_this_base_dir)
Users won't normally want to call this, it's only used from internal MRPT programs.
CArchiveStreamBase< STREAM > archiveFrom(STREAM &s)
Helper function to create a templatized wrapper CArchive object for a: MRPT's CStream, std::istream, std::ostream, std::stringstream.
bool loadFromFile(const std::string &fileName, int isColor=-1)
Load image from a file, whose format is determined from the extension (internally uses OpenCV)...
size_t getWidth() const override
Returns the width of the image in pixels.
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).
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'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).
std::string sensorLabel
An arbitrary label that can be used to identify the sensor.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
mrpt::system::TTimeStamp timestamp
The associated UTC time-stamp.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
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...
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)...
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...
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.
A class for storing images as grayscale or RGB bitmaps.
static struct FontData data