MRPT  2.0.5
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(100ms);
236  MRPT_LOG_INFO("Waiting for all threads to close...");
237  for (auto& t : lstThreads)
238  if (t.joinable()) t.join();
239 }
240 
242 {
243  try
244  {
245  m_isRunningMtx.lock();
246  m_isRunning = true;
247  m_isRunningMtx.unlock();
248 
249  runImpl();
250 
251  m_isRunningMtx.lock();
252  m_isRunning = false;
253  m_isRunningMtx.unlock();
254  }
255  catch (const std::exception& e)
256  {
257  m_isRunningMtx.lock();
258  m_isRunning = false;
259  m_isRunningMtx.unlock();
260  throw;
261  }
262 }
263 
266 {
267  // Show GPS mode:
269 
270  static auto last_t = mrpt::Clock::now();
271  const auto t_now = mrpt::Clock::now();
272  if (mrpt::system::timeDifference(last_t, t_now) < 1.0) return;
273  last_t = t_now;
274 
275  if (auto gps = std::dynamic_pointer_cast<mrpt::obs::CObservationGPS>(o);
276  gps)
277  {
278  dump_GPS_mode_info(*gps);
279  }
280  else if (auto imu =
281  std::dynamic_pointer_cast<mrpt::obs::CObservationIMU>(o);
282  imu)
283  {
284  dump_IMU_info(*imu);
285  }
286 }
287 
289  const mrpt::obs::CSensoryFrame& sf) const
290 {
292 
293  // Show GPS mode:
295  std::size_t idx = 0;
296  do
297  {
299  if (gps) dump_GPS_mode_info(*gps);
300  } while (gps);
301 
302  // Show IMU angles:
304  if (imu) dump_IMU_info(*imu);
305 }
306 
308  const mrpt::obs::CObservationGPS& o) const
309 {
310  if (o.has_GGA_datum())
311  {
313 
314  const auto fq = static_cast<int>(
315  o.getMsgByClass<Message_NMEA_GGA>().fields.fix_quality);
317  " GPS mode: " << fq << " label: " << o.sensorLabel);
318  }
319  {
320  std::stringstream ss;
321  o.getDescriptionAsText(ss);
322  MRPT_LOG_DEBUG_STREAM(ss.str());
323  }
324 }
325 
327 {
328  // Show IMU angles:
330  " IMU angles (degrees): "
331  "(yaw,pitch,roll)=(%.06f, %.06f, %.06f)",
335 }
336 
337 // ------------------------------------------------------
338 // SensorThread
339 // ------------------------------------------------------
340 void RawlogGrabberApp::SensorThread(std::string sensor_label)
341 {
342  try
343  {
344  std::string driver_name =
345  params.read_string(sensor_label, "driver", "", true);
346 
347  auto sensor =
349 
350  if (!sensor)
351  throw std::runtime_error(
352  std::string("Class name not recognized: ") + driver_name);
353 
354  // Load common & sensor specific parameters:
355  sensor->loadConfig(params, sensor_label);
356 
358  "[thread_" << sensor_label << "] Starting at "
359  << sensor->getProcessRate() << " Hz");
360 
361  ASSERT_ABOVE_(sensor->getProcessRate(), 0);
362 
363  // For imaging sensors, set external storage directory:
364  sensor->setPathForExternalImages(m_rawlog_ext_imgs_dir);
365 
366  // Init device:
367  sensor->initialize();
368 
370  rate.setRate(sensor->getProcessRate());
371 
372  while (!allThreadsMustExit())
373  {
374  // Process
375  sensor->doProcess();
376 
377  // Get new observations
379  sensor->getObservations(lstObjs);
380 
381  {
382  std::lock_guard<std::mutex> lock(cs_m_global_list_obs);
383  m_global_list_obs.insert(lstObjs.begin(), lstObjs.end());
384  }
385 
386  lstObjs.clear();
387 
388  // wait for the process period:
389  rate.sleep();
390  }
391 
392  sensor.reset();
393 
394  MRPT_LOG_INFO_FMT("[thread_%s] Closing...", sensor_label.c_str());
395  }
396  catch (const std::exception& e)
397  {
399  {
401  "Exception in SensorThread:\n"
402  << mrpt::exception_to_str(e));
403  }
404  allThreadsMustExit(true);
405  }
406  catch (...)
407  {
409  {
410  MRPT_LOG_ERROR("Untyped exception in SensorThread.");
411  }
412  allThreadsMustExit(true);
413  }
414 }
415 
417  const RawlogGrabberApp::TListObservations& list_obs)
418 {
419  using namespace mrpt::obs;
420 
421  // -----------------------
422  // USE SENSORY-FRAMES
423  // -----------------------
424  for (auto it = list_obs.begin(); it != list_obs.end(); ++it)
425  {
426  // If we have an action, save the SF and start a new one:
427  if (IS_DERIVED(*it->second, CAction))
428  {
429  CAction::Ptr act = std::dynamic_pointer_cast<CAction>(it->second);
430 
431  (*m_out_arch_ptr) << m_curSF;
433  "Saved SF with " << m_curSF.size() << " objects.");
434  m_curSF.clear();
435 
436  CActionCollection acts;
437  acts.insert(*act);
438  act.reset();
439 
440  (*m_out_arch_ptr) << acts;
441  }
442  else if (IS_CLASS(*it->second, CObservationOdometry))
443  {
445  std::dynamic_pointer_cast<CObservationOdometry>(it->second);
446 
447  auto act = CActionRobotMovement2D::Create();
448  act->timestamp = odom->timestamp;
449 
450  // Compute the increment since the last reading:
452  static CObservationOdometry last_odo;
453  static bool last_odo_first = true;
454 
455  mrpt::poses::CPose2D odo_incr;
456  int64_t lticks_incr, rticks_incr;
457 
458  if (last_odo_first)
459  {
460  last_odo_first = false;
461  odo_incr = mrpt::poses::CPose2D(0, 0, 0);
462  lticks_incr = rticks_incr = 0;
463  }
464  else
465  {
466  odo_incr = odom->odometry - last_odo.odometry;
467  lticks_incr =
468  odom->encoderLeftTicks - last_odo.encoderLeftTicks;
469  rticks_incr =
470  odom->encoderRightTicks - last_odo.encoderRightTicks;
471 
472  last_odo = *odom;
473  }
474 
475  // Save as action & dump to file:
476  act->computeFromOdometry(odo_incr, odomOpts);
477 
478  act->hasEncodersInfo = true;
479  act->encoderLeftTicks = lticks_incr;
480  act->encoderRightTicks = rticks_incr;
481 
482  act->hasVelocities = true;
483  act->velocityLocal = odom->velocityLocal;
484 
485  (*m_out_arch_ptr) << m_curSF;
486 
488  "Saved SF with " << m_curSF.size() << " objects.");
489  m_curSF.clear();
490 
491  CActionCollection acts;
492  acts.insert(*act);
493  act.reset();
494 
495  (*m_out_arch_ptr) << acts;
496  {
497  auto lk = mrpt::lockHelper(results_mtx);
498  rawlog_saved_objects += 2; // m_curSF + acts;
499  }
500  }
501  else if (IS_DERIVED(*it->second, CObservation))
502  {
503  CObservation::Ptr obs =
504  std::dynamic_pointer_cast<CObservation>(it->second);
505 
506  // First, check if inserting this OBS into the SF would
507  // overflow "SF_max_time_span":
508  if (m_curSF.size() != 0 &&
510  m_curSF.getObservationByIndex(0)->timestamp,
511  obs->timestamp) > SF_max_time_span)
512  {
514 
515  // Save and start a new one:
516  (*m_out_arch_ptr) << m_curSF;
517  {
518  auto lk = mrpt::lockHelper(results_mtx);
520  }
521 
523  "Saved SF with " << m_curSF.size() << " objects.");
524  m_curSF.clear();
525  }
526 
527  // Now, insert the observation in the SF:
528  m_curSF.insert(obs);
529  }
530  else
532  "*** ERROR *** Class is not an action or an "
533  "observation");
534  }
535 }
536 
538  const RawlogGrabberApp::TListObservations& list_obs)
539 {
540  // ---------------------------
541  // DO NOT USE SENSORY-FRAMES
542  // ---------------------------
543  for (auto& ob : list_obs)
544  {
545  auto& obj_ptr = ob.second;
546  (*m_out_arch_ptr) << *obj_ptr;
547  {
548  auto lk = mrpt::lockHelper(results_mtx);
550  }
551 
552  dump_verbose_info(obj_ptr);
553  }
554 
555  if (!list_obs.empty())
556  {
557  MRPT_LOG_INFO_STREAM("Saved " << list_obs.size() << " objects.");
558  }
559 }
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
#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.5 Git: eda5ade6c Tue Aug 4 12:48:50 2020 +0200 at mar ago 4 13:00:11 CEST 2020