MRPT  2.0.4
RawlogGrabberApp.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 #include "apps-precomp.h" // Precompiled headers
11 //
12 #include <mrpt/3rdparty/tclap/CmdLine.h>
15 #include <mrpt/core/lock_helper.h>
16 #include <mrpt/core/round.h>
18 #include <mrpt/img/CImage.h>
26 #include <mrpt/obs/CSensoryFrame.h>
28 #include <mrpt/system/CRateTimer.h>
29 #include <mrpt/system/filesystem.h>
30 #include <mrpt/system/os.h>
32 
33 #include <thread>
34 
35 using namespace mrpt::apps;
36 
38  : mrpt::system::COutputLogger("RawlogGrabberApp")
39 {
40 }
41 
42 void RawlogGrabberApp::initialize(int argc, const char** argv)
43 {
45 
46  if ((getenv("MRPT_HWDRIVERS_VERBOSE") != nullptr) &&
47  atoi(getenv("MRPT_HWDRIVERS_VERBOSE")) != 0)
48  {
50  }
51 
52  MRPT_LOG_INFO(" rawlog-grabber - Part of the MRPT");
54  " MRPT C++ Library: %s - Sources timestamp: %s\n",
57 
58  // Declare the supported options.
59  TCLAP::CmdLine cmd(
60  "rawlog-grabber", ' ', mrpt::system::MRPT_getVersion().c_str());
61 
62  TCLAP::UnlabeledValueArg<std::string> argConfigFile(
63  "config", "Config file", true, "", "<configFile.ini>", cmd);
64  TCLAP::ValueArg<std::string> argPlugins(
65  "p", "plugins",
66  "Load one or more plug-in modules (.so/.dll) with additional sensor "
67  "drivers (comma-separated list)",
68  false, "", "myModule.so", cmd);
69 
70  // Process arguments:
71  if (!cmd.parse(argc, argv))
72  THROW_EXCEPTION("CLI arguments parsing tells we should exit.");
73 
74  ASSERT_FILE_EXISTS_(argConfigFile.getValue());
75  params.setContent(mrpt::io::file_get_contents(argConfigFile.getValue()));
76 
77  if (argPlugins.isSet())
78  mrpt::system::loadPluginModules(argPlugins.getValue());
79 
80  MRPT_END
81 }
82 
84 {
85  using namespace mrpt;
86  using namespace mrpt::system;
87  using namespace mrpt::hwdrivers;
88  using namespace mrpt::config;
89  using namespace mrpt::serialization;
90  using namespace mrpt::img;
91  using namespace mrpt::obs;
92  using namespace mrpt::poses;
93  using namespace std;
94 
95  const std::string GLOBAL_SECT = "global";
96 
97  // ------------------------------------------
98  // Load config from file:
99  // ------------------------------------------
100  string rawlog_prefix = "dataset";
101  int time_between_launches = 300;
102  bool use_sensoryframes = false;
103  int GRABBER_PERIOD_MS = 1000;
104  int rawlog_GZ_compress_level = 1; // 0: No compress, 1-9: compress level
105 
106  MRPT_LOAD_CONFIG_VAR(rawlog_prefix, string, params, GLOBAL_SECT);
107  MRPT_LOAD_CONFIG_VAR(time_between_launches, int, params, GLOBAL_SECT);
108  MRPT_LOAD_CONFIG_VAR(SF_max_time_span, float, params, GLOBAL_SECT);
109  MRPT_LOAD_CONFIG_VAR(use_sensoryframes, bool, params, GLOBAL_SECT);
110  MRPT_LOAD_CONFIG_VAR(GRABBER_PERIOD_MS, int, params, GLOBAL_SECT);
111 
112  MRPT_LOAD_CONFIG_VAR(rawlog_GZ_compress_level, int, params, GLOBAL_SECT);
113 
114  // Build full rawlog file name:
115  string rawlog_postfix = "_";
116 
117  // rawlog_postfix += dateTimeToString( now() );
119  mrpt::system::timestampToParts(now(), parts, true);
120  rawlog_postfix += format(
121  "%04u-%02u-%02u_%02uh%02um%02us", (unsigned int)parts.year,
122  (unsigned int)parts.month, (unsigned int)parts.day,
123  (unsigned int)parts.hour, (unsigned int)parts.minute,
124  (unsigned int)parts.second);
125 
126  rawlog_postfix = mrpt::system::fileNameStripInvalidChars(rawlog_postfix);
127 
128  // Only set this if we want externally stored images:
130  rawlog_prefix +
131  fileNameStripInvalidChars(rawlog_postfix + string("_Images"));
132 
133  // Also, set the path in CImage to enable online visualization in a GUI
134  // window:
135  CImage::setImagesPathBase(m_rawlog_ext_imgs_dir);
136 
137  rawlog_postfix += string(".rawlog");
138  rawlog_postfix = fileNameStripInvalidChars(rawlog_postfix);
139 
140  results_mtx.lock();
141  rawlog_filename = rawlog_prefix + rawlog_postfix;
142  results_mtx.unlock();
143 
144  MRPT_LOG_INFO_STREAM("Output rawlog filename: " << rawlog_filename);
145  MRPT_LOG_INFO_STREAM("External image storage: " << m_rawlog_ext_imgs_dir);
146 
147  // ----------------------------------------------
148  // Launch threads:
149  // ----------------------------------------------
150  std::vector<std::string> sections;
151  params.getAllSections(sections);
152 
153  vector<std::thread> lstThreads;
154 
155  for (auto& section : sections)
156  {
157  if (section == GLOBAL_SECT || section.empty() ||
158  params.read_bool(section, "rawlog-grabber-ignore", false, false))
159  continue; // This is not a sensor:
160 
161  std::thread& newThread = lstThreads.emplace_back(
162  &RawlogGrabberApp::SensorThread, this, section);
163 
164  mrpt::system::thread_name(section, newThread);
165 
166  std::this_thread::sleep_for(
167  std::chrono::milliseconds(time_between_launches));
168  }
169 
170  // ----------------------------------------------
171  // Run:
172  // ----------------------------------------------
174  auto out_arch_obj = archiveFrom(out_file);
175  m_out_arch_ptr = &out_arch_obj;
176 
177  out_file.open(rawlog_filename, rawlog_GZ_compress_level);
178 
179  CGenericSensor::TListObservations copy_of_m_global_list_obs;
180 
181  MRPT_LOG_INFO_STREAM("Press any key to exit program");
182 
183  mrpt::system::CTicTac run_timer;
184  run_timer.Tic();
185 
186  auto lambdaProcessPending = [&]() {
188  copy_of_m_global_list_obs.clear();
189 
190  if (!m_global_list_obs.empty())
191  {
192  auto itEnd = m_global_list_obs.begin();
193  std::advance(itEnd, m_global_list_obs.size() / 2);
194  copy_of_m_global_list_obs.insert(m_global_list_obs.begin(), itEnd);
195  m_global_list_obs.erase(m_global_list_obs.begin(), itEnd);
196  }
197 
198  if (use_sensoryframes)
199  process_observations_for_sf(copy_of_m_global_list_obs);
200  else
201  process_observations_for_nonsf(copy_of_m_global_list_obs);
202  };
203 
204  while (!os::kbhit() && !allThreadsMustExit)
205  {
206  // Check "run for X seconds" flag:
207  {
208  auto lk = mrpt::lockHelper(params_mtx);
209  if (run_for_seconds > 0 && run_timer.Tac() > run_for_seconds) break;
210  }
211 
212  // See if we have observations and process them:
213  lambdaProcessPending();
214 
215  std::this_thread::sleep_for(
216  std::chrono::milliseconds(GRABBER_PERIOD_MS));
217  }
218 
219  if (allThreadsMustExit)
220  {
222  "[main thread] Ended due to other thread signal to exit "
223  "application.");
224  }
225 
226  // Final check of pending objects:
227  lambdaProcessPending();
228 
229  // Flush file to disk:
230  out_file.close();
231 
232  // Wait all threads:
233  // ----------------------------
234  allThreadsMustExit = true;
235  std::this_thread::sleep_for(300ms);
236 
237  MRPT_LOG_INFO("Waiting for all threads to close...");
238 
239  for (auto& lstThread : lstThreads) lstThread.join();
240 }
241 
243 {
244  try
245  {
246  m_isRunningMtx.lock();
247  m_isRunning = true;
248  m_isRunningMtx.unlock();
249 
250  runImpl();
251 
252  m_isRunningMtx.lock();
253  m_isRunning = false;
254  m_isRunningMtx.unlock();
255  }
256  catch (const std::exception& e)
257  {
258  m_isRunningMtx.lock();
259  m_isRunning = false;
260  m_isRunningMtx.unlock();
261  throw;
262  }
263 }
264 
267 {
268  // Show GPS mode:
270 
271  static auto last_t = mrpt::Clock::now();
272  const auto t_now = mrpt::Clock::now();
273  if (mrpt::system::timeDifference(last_t, t_now) < 1.0) return;
274  last_t = t_now;
275 
276  if (auto gps = std::dynamic_pointer_cast<mrpt::obs::CObservationGPS>(o);
277  gps)
278  {
279  dump_GPS_mode_info(*gps);
280  }
281  else if (auto imu =
282  std::dynamic_pointer_cast<mrpt::obs::CObservationIMU>(o);
283  imu)
284  {
285  dump_IMU_info(*imu);
286  }
287 }
288 
290  const mrpt::obs::CSensoryFrame& sf) const
291 {
293 
294  // Show GPS mode:
296  std::size_t idx = 0;
297  do
298  {
300  if (gps) dump_GPS_mode_info(*gps);
301  } while (gps);
302 
303  // Show IMU angles:
305  if (imu) dump_IMU_info(*imu);
306 }
307 
309  const mrpt::obs::CObservationGPS& o) const
310 {
311  if (o.has_GGA_datum())
312  {
314 
315  const auto fq = static_cast<int>(
316  o.getMsgByClass<Message_NMEA_GGA>().fields.fix_quality);
318  " GPS mode: " << fq << " label: " << o.sensorLabel);
319  }
320  {
321  std::stringstream ss;
322  o.getDescriptionAsText(ss);
323  MRPT_LOG_DEBUG_STREAM(ss.str());
324  }
325 }
326 
328 {
329  // Show IMU angles:
331  " IMU angles (degrees): "
332  "(yaw,pitch,roll)=(%.06f, %.06f, %.06f)",
336 }
337 
338 // ------------------------------------------------------
339 // SensorThread
340 // ------------------------------------------------------
341 void RawlogGrabberApp::SensorThread(std::string sensor_label)
342 {
343  try
344  {
345  std::string driver_name =
346  params.read_string(sensor_label, "driver", "", true);
347 
348  auto sensor =
350 
351  if (!sensor)
352  throw std::runtime_error(
353  std::string("Class name not recognized: ") + driver_name);
354 
355  // Load common & sensor specific parameters:
356  sensor->loadConfig(params, sensor_label);
357 
359  "[thread_" << sensor_label << "] Starting at "
360  << sensor->getProcessRate() << " Hz");
361 
362  ASSERT_ABOVE_(sensor->getProcessRate(), 0);
363 
364  // For imaging sensors, set external storage directory:
365  sensor->setPathForExternalImages(m_rawlog_ext_imgs_dir);
366 
367  // Init device:
368  sensor->initialize();
369 
371  rate.setRate(sensor->getProcessRate());
372 
373  while (!allThreadsMustExit)
374  {
375  // Process
376  sensor->doProcess();
377 
378  // Get new observations
380  sensor->getObservations(lstObjs);
381 
382  {
383  std::lock_guard<std::mutex> lock(cs_m_global_list_obs);
384  m_global_list_obs.insert(lstObjs.begin(), lstObjs.end());
385  }
386 
387  lstObjs.clear();
388 
389  // wait for the process period:
390  rate.sleep();
391  }
392 
393  sensor.reset();
394 
395  MRPT_LOG_INFO_FMT("[thread_%s] Closing...", sensor_label.c_str());
396  }
397  catch (const std::exception& e)
398  {
400  {
402  "Exception in SensorThread:\n"
403  << mrpt::exception_to_str(e));
404  }
405  allThreadsMustExit = true;
406  }
407  catch (...)
408  {
410  {
411  MRPT_LOG_ERROR("Untyped exception in SensorThread.");
412  }
413  allThreadsMustExit = true;
414  }
415 }
416 
418  const RawlogGrabberApp::TListObservations& list_obs)
419 {
420  using namespace mrpt::obs;
421 
422  // -----------------------
423  // USE SENSORY-FRAMES
424  // -----------------------
425  for (auto it = list_obs.begin(); it != list_obs.end(); ++it)
426  {
427  // If we have an action, save the SF and start a new one:
428  if (IS_DERIVED(*it->second, CAction))
429  {
430  CAction::Ptr act = std::dynamic_pointer_cast<CAction>(it->second);
431 
432  (*m_out_arch_ptr) << m_curSF;
434  "Saved SF with " << m_curSF.size() << " objects.");
435  m_curSF.clear();
436 
437  CActionCollection acts;
438  acts.insert(*act);
439  act.reset();
440 
441  (*m_out_arch_ptr) << acts;
442  }
443  else if (IS_CLASS(*it->second, CObservationOdometry))
444  {
446  std::dynamic_pointer_cast<CObservationOdometry>(it->second);
447 
448  auto act = CActionRobotMovement2D::Create();
449  act->timestamp = odom->timestamp;
450 
451  // Compute the increment since the last reading:
453  static CObservationOdometry last_odo;
454  static bool last_odo_first = true;
455 
456  mrpt::poses::CPose2D odo_incr;
457  int64_t lticks_incr, rticks_incr;
458 
459  if (last_odo_first)
460  {
461  last_odo_first = false;
462  odo_incr = mrpt::poses::CPose2D(0, 0, 0);
463  lticks_incr = rticks_incr = 0;
464  }
465  else
466  {
467  odo_incr = odom->odometry - last_odo.odometry;
468  lticks_incr =
469  odom->encoderLeftTicks - last_odo.encoderLeftTicks;
470  rticks_incr =
471  odom->encoderRightTicks - last_odo.encoderRightTicks;
472 
473  last_odo = *odom;
474  }
475 
476  // Save as action & dump to file:
477  act->computeFromOdometry(odo_incr, odomOpts);
478 
479  act->hasEncodersInfo = true;
480  act->encoderLeftTicks = lticks_incr;
481  act->encoderRightTicks = rticks_incr;
482 
483  act->hasVelocities = true;
484  act->velocityLocal = odom->velocityLocal;
485 
486  (*m_out_arch_ptr) << m_curSF;
487 
489  "Saved SF with " << m_curSF.size() << " objects.");
490  m_curSF.clear();
491 
492  CActionCollection acts;
493  acts.insert(*act);
494  act.reset();
495 
496  (*m_out_arch_ptr) << acts;
497  {
498  auto lk = mrpt::lockHelper(results_mtx);
499  rawlog_saved_objects += 2; // m_curSF + acts;
500  }
501  }
502  else if (IS_DERIVED(*it->second, CObservation))
503  {
504  CObservation::Ptr obs =
505  std::dynamic_pointer_cast<CObservation>(it->second);
506 
507  // First, check if inserting this OBS into the SF would
508  // overflow "SF_max_time_span":
509  if (m_curSF.size() != 0 &&
511  m_curSF.getObservationByIndex(0)->timestamp,
512  obs->timestamp) > SF_max_time_span)
513  {
515 
516  // Save and start a new one:
517  (*m_out_arch_ptr) << m_curSF;
518  {
519  auto lk = mrpt::lockHelper(results_mtx);
521  }
522 
524  "Saved SF with " << m_curSF.size() << " objects.");
525  m_curSF.clear();
526  }
527 
528  // Now, insert the observation in the SF:
529  m_curSF.insert(obs);
530  }
531  else
533  "*** ERROR *** Class is not an action or an "
534  "observation");
535  }
536 }
537 
539  const RawlogGrabberApp::TListObservations& list_obs)
540 {
541  // ---------------------------
542  // DO NOT USE SENSORY-FRAMES
543  // ---------------------------
544  for (auto& ob : list_obs)
545  {
546  auto& obj_ptr = ob.second;
547  (*m_out_arch_ptr) << *obj_ptr;
548  {
549  auto lk = mrpt::lockHelper(results_mtx);
551  }
552 
553  dump_verbose_info(obj_ptr);
554  }
555 
556  if (!list_obs.empty())
557  {
558  MRPT_LOG_INFO_STREAM("Saved " << list_obs.size() << " objects.");
559  }
560 }
void clear()
Clear all current observations.
double Tac() noexcept
Stops the stopwatch.
Definition: CTicTac.cpp:87
void timestampToParts(TTimeStamp t, TTimeParts &p, bool localTime=false)
Gets the individual parts of a date/time (days, hours, minutes, seconds) - UTC time or local time...
Definition: datetime.cpp:50
bool has_GGA_datum() const
true if the corresponding field exists in messages.
A class for calling sleep() in a loop, such that the amount of sleep time will be computed to make th...
void insert(const CObservation::Ptr &obs)
Inserts a new observation to the list: The pointer to the objects is copied, thus DO NOT delete the p...
mrpt::serialization::CArchive * m_out_arch_ptr
#define MRPT_START
Definition: exceptions.h:241
std::string read_string(const std::string &section, const std::string &name, const std::string &defaultValue, bool failIfNotFound=false) const
std::vector< double > rawMeasurements
The accelerometer and/or gyroscope measurements taken by the IMU at the given timestamp.
std::mutex results_mtx
Acquire this mutex if reading these output variables while the app is running.
#define THROW_EXCEPTION(msg)
Definition: exceptions.h:67
std::string std::string format(std::string_view fmt, ARGS &&... args)
Definition: format.h:26
bool open(const std::string &fileName, int compress_level=1, mrpt::optional_ref< std::string > error_msg=std::nullopt)
Open a file for write, choosing the compression level.
mrpt::poses::CPose2D odometry
The absolute odometry measurement (IT IS NOT INCREMENTAL)
TListObservations m_global_list_obs
bool sleep()
Sleeps for some time, such as the return of this method is 1/rate (seconds) after the return of the p...
Definition: CRateTimer.cpp:30
orientation pitch absolute value (global/navigation frame) (rad)
std::string m_rawlog_ext_imgs_dir
Directory where to save externally stored images, only for CCameraSensor&#39;s.
A high-performance stopwatch, with typical resolution of nanoseconds.
void setMinLoggingLevel(const VerbosityLevel level)
Set the minimum logging level for which the incoming logs are going to be taken into account...
mrpt::system::TTimeStamp now()
A shortcut for system::getCurrentTime.
Definition: datetime.h:86
Contains classes for various device interfaces.
T::Ptr getObservationByClass(size_t ith=0) const
Returns the i&#39;th observation of a given class (or of a descendant class), or nullptr if there is no s...
STL namespace.
std::string MRPT_getCompilationDate()
Returns the MRPT source code timestamp, according to the Reproducible-Builds specifications: https://...
Definition: os.cpp:165
std::string fileNameStripInvalidChars(const std::string &filename, const char replacement_to_invalid_chars='_')
Replace invalid filename chars by underscores (&#39;_&#39;) or any other user-given char. ...
Definition: filesystem.cpp:329
This class stores measurements from an Inertial Measurement Unit (IMU) (attitude estimation, raw gyroscope and accelerometer values), altimeters or magnetometers.
mrpt::system::COutputLogger COutputLogger
The parameter to be passed to "computeFromOdometry".
static time_point now() noexcept
Returns the current time using the currently selected Clock source.
Definition: Clock.cpp:94
mrpt::hwdrivers::CGenericSensor::TListObservations TListObservations
void thread_name(const std::string &name, std::thread &theThread)
Sets the name of the given thread; useful for debuggers.
Definition: thread_name.cpp:63
Declares a class for storing a collection of robot actions.
bool show_sensor_thread_exceptions
If enabled (default), exceptions in sensor threads will be reported to std::cerr. ...
void dump_verbose_info(const mrpt::serialization::CSerializable::Ptr &o) const
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
VerbosityLevel getMinLoggingLevel() const
LockHelper< T > lockHelper(T &t)
Syntactic sugar to easily create a locker to any kind of std::mutex.
Definition: lock_helper.h:50
const CObservation::Ptr & getObservationByIndex(size_t idx) const
Returns the i&#39;th observation in the list (0=first).
void getDescriptionAsText(std::ostream &o) const override
Build a detailed, multi-line textual description of the observation contents and dump it to the outpu...
#define MRPT_LOG_DEBUG_FMT(_FMT_STRING,...)
Use: MRPT_LOG_DEBUG_FMT("i=%u", i);
void initialize(int argc, const char **argv)
Initializes the application from CLI parameters.
The parts of a date/time (it&#39;s like the standard &#39;tm&#39; but with fractions of seconds).
Definition: datetime.h:49
static Ptr createSensorPtr(const std::string &className)
Just like createSensor, but returning a smart pointer to the newly created sensor object...
std::string rawlog_filename
The generated .rawlog file.
void run()
Runs with the current parameter set.
#define IS_DERIVED(obj, class_name)
True if the given reference to object (derived from mrpt::rtti::CObject) is an instance of the given ...
Definition: CObject.h:151
uint8_t day
Month (1-12)
Definition: datetime.h:53
This namespace contains representation of robot actions and observations.
Declares a class for storing a "sensory frame", a set of "observations" taken by the robot approximat...
Definition: CSensoryFrame.h:51
#define IS_CLASS(obj, class_name)
True if the given reference to object (derived from mrpt::rtti::CObject) is of the given class...
Definition: CObject.h:146
std::atomic_bool allThreadsMustExit
#define MRPT_LOG_DEBUG_STREAM(__CONTENTS)
Use: MRPT_LOG_DEBUG_STREAM("Var=" << value << " foo=" << foo_var);
void SensorThread(std::string sensor_label)
MSG_CLASS & getMsgByClass()
Returns a reference to the message in the list CObservationGPS::messages of the requested class...
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
void getAllSections(std::vector< std::string > &sections) const override
Returns a list with all the section names.
bool loadPluginModules(const std::string &moduleFileNames, mrpt::optional_ref< std::string > outErrorMsgs=std::nullopt)
Like loadPluginModule(), but loads a comma (,) separated list of "plug-in" modules.
void process_observations_for_nonsf(const TListObservations &list_obs)
Declares a class for storing a robot action.
Definition: CAction.h:24
TCLAP::CmdLine cmd("system_control_rate_timer_example")
double second
Minute (0-59)
Definition: datetime.h:56
#define MRPT_LOAD_CONFIG_VAR( variableName, variableType, configFileObject, sectionNameStr)
An useful macro for loading variables stored in a INI-like file under a key with the same name that t...
void setRate(const double rate_hz)
Changes the object loop rate (Hz)
Definition: CRateTimer.cpp:25
#define MRPT_LOG_INFO_STREAM(__CONTENTS)
double run_for_seconds
If >0, run() will return after this period (in seconds)
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[]
int32_t encoderLeftTicks
For differential-driven robots: The ticks count for each wheel in ABSOLUTE VALUE (IT IS NOT INCREMENT...
uint8_t minute
Hour (0-23)
Definition: datetime.h:55
std::multimap< mrpt::system::TTimeStamp, mrpt::serialization::CSerializable::Ptr > TListObservations
void process_observations_for_sf(const TListObservations &list_obs)
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
Definition: CPose2D.h:39
Declares a class that represents any robot&#39;s observation.
Definition: CObservation.h:43
#define MRPT_LOG_ERROR(_STRING)
std::size_t rawlog_saved_objects
Counter of saved objects.
bool read_bool(const std::string &section, const std::string &name, bool defaultValue, bool failIfNotFound=false) const
void setContent(const std::vector< std::string > &stringList)
Changes the contents of the virtual "config file".
constexpr double RAD2DEG(const double x)
Radians to degrees.
#define ASSERT_ABOVE_(__A, __B)
Definition: exceptions.h:155
#define MRPT_END
Definition: exceptions.h:245
bool kbhit() noexcept
An OS-independent version of kbhit, which returns true if a key has been pushed.
Definition: os.cpp:403
std::string file_get_contents(const std::string &fileName)
Loads an entire text file and return its contents as a single std::string.
uint8_t month
The year.
Definition: datetime.h:52
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
uint8_t hour
Day (1-31)
Definition: datetime.h:54
const int argc
orientation yaw absolute value (global/navigation frame) (rad)
double timeDifference(const mrpt::system::TTimeStamp t_first, const mrpt::system::TTimeStamp t_later)
Returns the time difference from t1 to t2 (positive if t2 is posterior to t1), in seconds...
Definition: datetime.h:123
orientation roll absolute value (global/navigation frame) (rad)
std::string MRPT_getVersion()
Returns a string describing the MRPT version.
Definition: os.cpp:198
An observation of the current (cumulative) odometry for a wheeled robot.
Saves data to a file and transparently compress the data using the given compression level...
void Tic() noexcept
Starts the stopwatch.
Definition: CTicTac.cpp:76
#define ASSERT_FILE_EXISTS_(FIL)
Definition: filesystem.h:22
std::mutex params_mtx
Acquire this mutex if changing parameters while the app is running.
void dump_GPS_mode_info(const mrpt::obs::CObservationGPS &o) const
This class stores messages from GNSS or GNSS+IMU devices, from consumer-grade inexpensive GPS receive...
#define MRPT_LOG_ERROR_STREAM(__CONTENTS)
size_t size() const
Returns the number of observations in the list.
mrpt::config::CConfigFileMemory params
Populated in initialize().
void dump_IMU_info(const mrpt::obs::CObservationIMU &o) const
#define MRPT_LOG_INFO_FMT(_FMT_STRING,...)
#define MRPT_LOG_INFO(_STRING)
mrpt::obs::CSensoryFrame m_curSF
void insert(CAction &action)
Add a new object to the list.



Page generated by Doxygen 1.8.14 for MRPT 2.0.4 Git: 33de1d0ad Sat Jun 20 11:02:42 2020 +0200 at sáb jun 20 17:35:17 CEST 2020