| |
- pybind11_builtins.pybind11_object(builtins.object)
-
- CControlledRateTimer
- CDirectoryExplorer
- CFileSystemWatcher
- CObservable
- CObserver
- COutputLoggerStreamWrapper
- CRateTimer
- CTicTac
- CTimeLogger
- CTimeLoggerEntry
- CTimeLoggerSaveAtDtor
- ConsoleBackgroundColor
- ConsoleForegroundColor
- ConsoleTextStyle
- TProcessPriority
- TThreadPriority
- TTimeParts
- VerbosityLevel
- WorkerThreadsPool
- mrptEvent
-
- mrptEventOnDestroy
class CControlledRateTimer(pybind11_builtins.pybind11_object) |
|
A class for calling sleep() in a loop, such that the amount of sleep time
will be computed to make the loop run at the desired rate (in Hz).
This class implements a PI controller on top of a vanilla CRateTimer object,
ensuring a high accuracy in achieved execution rates. Note that this is done
by setting a slightly-higher rate ("control action") to the internal
CRateTimer, such that the error between the user-provided expected rate and
the actual measured rate (low-pass filtered) is decreased by means of a PI
controller.
Note that rates higher than a few kHz are not attainable in all CPUs and/or
kernel versions. Find below some graphs illustrating how this class tries to
achieve a constant setpoint rate (given by the user), reacting to changes in
the setpoint values:
![controlled rate timer plots](CControlledRateTimer_example.png)
This graphs is generated with the example:
`system_control_rate_timer_example --rate1 2000.0 --rate2 4000.0`
All the parameters for the PI controller and low-pass filter (rate estimator)
are settable by the user to adapt them to specific needs.
Control law by [Francisco Jose MaƱas
Alvarez](https://github.com/FranciscoJManasAlvarez)
[New in MRPT 2.0.4] |
|
- Method resolution order:
- CControlledRateTimer
- pybind11_builtins.pybind11_object
- builtins.object
Methods defined here:
- __init__(...)
- __init__(*args, **kwargs)
Overloaded function.
1. __init__(self: mrpt.pymrpt.mrpt.system.CControlledRateTimer) -> None
doc
2. __init__(self: mrpt.pymrpt.mrpt.system.CControlledRateTimer, rate_hz: float) -> None
3. __init__(self: mrpt.pymrpt.mrpt.system.CControlledRateTimer, arg0: mrpt.pymrpt.mrpt.system.CControlledRateTimer) -> None
- actualControlledRate(...)
- actualControlledRate(self: mrpt.pymrpt.mrpt.system.CControlledRateTimer) -> float
Gets the actual controller output: the rate (Hz) of the internal
CRateTimer object.
C++: mrpt::system::CControlledRateTimer::actualControlledRate() const --> double
- assign(...)
- assign(self: mrpt.pymrpt.mrpt.system.CControlledRateTimer, : mrpt.pymrpt.mrpt.system.CControlledRateTimer) -> mrpt.pymrpt.mrpt.system.CControlledRateTimer
C++: mrpt::system::CControlledRateTimer::operator=(const class mrpt::system::CControlledRateTimer &) --> class mrpt::system::CControlledRateTimer &
- controllerParam_Kp(...)
- controllerParam_Kp(*args, **kwargs)
Overloaded function.
1. controllerParam_Kp(self: mrpt.pymrpt.mrpt.system.CControlledRateTimer) -> float
PI controller Kp parameter [default=1.0]
C++: mrpt::system::CControlledRateTimer::controllerParam_Kp() const --> double
2. controllerParam_Kp(self: mrpt.pymrpt.mrpt.system.CControlledRateTimer, v: float) -> None
C++: mrpt::system::CControlledRateTimer::controllerParam_Kp(double) --> void
- controllerParam_Ti(...)
- controllerParam_Ti(*args, **kwargs)
Overloaded function.
1. controllerParam_Ti(self: mrpt.pymrpt.mrpt.system.CControlledRateTimer) -> float
PI controller Ti parameter [default=0.0194]
C++: mrpt::system::CControlledRateTimer::controllerParam_Ti() const --> double
2. controllerParam_Ti(self: mrpt.pymrpt.mrpt.system.CControlledRateTimer, v: float) -> None
C++: mrpt::system::CControlledRateTimer::controllerParam_Ti(double) --> void
- estimatedRate(...)
- estimatedRate(self: mrpt.pymrpt.mrpt.system.CControlledRateTimer) -> float
Gets the latest estimated run rate (Hz), which comes from actual period
measurement, low-pass filtered.
C++: mrpt::system::CControlledRateTimer::estimatedRate() const --> double
- estimatedRateRaw(...)
- estimatedRateRaw(self: mrpt.pymrpt.mrpt.system.CControlledRateTimer) -> float
Last actual execution rate measured (Hz), without low-pass filtering
C++: mrpt::system::CControlledRateTimer::estimatedRateRaw() const --> double
- followErrorRatioToRaiseWarning(...)
- followErrorRatioToRaiseWarning(*args, **kwargs)
Overloaded function.
1. followErrorRatioToRaiseWarning(self: mrpt.pymrpt.mrpt.system.CControlledRateTimer) -> float
Get/set ratio threshold for issuing a warning (via COutputLogger
interface) if the achieved rate is not this close to the set-point
[Default=0.2, =20%]
C++: mrpt::system::CControlledRateTimer::followErrorRatioToRaiseWarning() const --> double
2. followErrorRatioToRaiseWarning(self: mrpt.pymrpt.mrpt.system.CControlledRateTimer, v: float) -> None
C++: mrpt::system::CControlledRateTimer::followErrorRatioToRaiseWarning(double) --> void
- lowPassParam_a0(...)
- lowPassParam_a0(*args, **kwargs)
Overloaded function.
1. lowPassParam_a0(self: mrpt.pymrpt.mrpt.system.CControlledRateTimer) -> float
Low-pass filter a0 value [default=0.9]:
estimation = a0*input + (1-a0)*former_estimation
C++: mrpt::system::CControlledRateTimer::lowPassParam_a0() const --> double
2. lowPassParam_a0(self: mrpt.pymrpt.mrpt.system.CControlledRateTimer, v: float) -> None
C++: mrpt::system::CControlledRateTimer::lowPassParam_a0(double) --> void
- setRate(...)
- setRate(self: mrpt.pymrpt.mrpt.system.CControlledRateTimer, rate_hz: float) -> None
Changes the object loop rate (Hz)
C++: mrpt::system::CControlledRateTimer::setRate(const double) --> void
- sleep(...)
- sleep(self: mrpt.pymrpt.mrpt.system.CControlledRateTimer) -> bool
Sleeps for some time, such as the return of this method is 1/rate
(seconds)
after the return of the previous call.
false if the rate could not be achieved ("we are already late"),
true if all went right.
C++: mrpt::system::CControlledRateTimer::sleep() --> bool
Static methods inherited from pybind11_builtins.pybind11_object:
- __new__(*args, **kwargs) from pybind11_builtins.pybind11_type
- Create and return a new object. See help(type) for accurate signature.
|
class CDirectoryExplorer(pybind11_builtins.pybind11_object) |
|
This class allows the enumeration of the files/directories that exist into a
given path.
The only existing method is "explore" and returns the list of found files &
directories.
Refer to the example in /samples/UTILS/directoryExplorer
CFileSystemWatcher |
|
- Method resolution order:
- CDirectoryExplorer
- pybind11_builtins.pybind11_object
- builtins.object
Methods defined here:
- __init__(...)
- __init__(self: mrpt.pymrpt.mrpt.system.CDirectoryExplorer) -> None
Static methods defined here:
- explore(...) from builtins.PyCapsule
- explore(*args, **kwargs)
Overloaded function.
1. explore(path: str, mask: int) -> List[mrpt::system::CDirectoryExplorer::TFileInfo]
The path of the directory to examine must be passed to this constructor,
among the
According to the following parameters, the object will collect the list
of files, which
can be modified later through other methods in this class.
The path to examine (IT MUST BE A DIRECTORY), e.g
"d:\temp\", or "/usr/include/"
One or the OR'ed combination of the values
"FILE_ATTRIB_ARCHIVE" and "FILE_ATTRIB_DIRECTORY", depending on what file
types do you want in the list (These values are platform-independent).
The list of found files/directories is stored here.
sortByName
C++: mrpt::system::CDirectoryExplorer::explore(const std::string &, const unsigned long) --> class std::deque<struct mrpt::system::CDirectoryExplorer::TFileInfo>
2. explore(path: str, mask: int, outList: List[mrpt::system::CDirectoryExplorer::TFileInfo]) -> None
C++: mrpt::system::CDirectoryExplorer::explore(const std::string &, const unsigned long, class std::deque<struct mrpt::system::CDirectoryExplorer::TFileInfo> &) --> void
- filterByExtension(...) from builtins.PyCapsule
- filterByExtension(lstFiles: List[mrpt::system::CDirectoryExplorer::TFileInfo], extension: str) -> None
Remove from the list of files those whose extension does not coincide
(without case) with the given one.
Example: filterByExtension(lst,"txt");
C++: mrpt::system::CDirectoryExplorer::filterByExtension(class std::deque<struct mrpt::system::CDirectoryExplorer::TFileInfo> &, const std::string &) --> void
- sortByName(...) from builtins.PyCapsule
- sortByName(*args, **kwargs)
Overloaded function.
1. sortByName(lstFiles: List[mrpt::system::CDirectoryExplorer::TFileInfo]) -> None
2. sortByName(lstFiles: List[mrpt::system::CDirectoryExplorer::TFileInfo], ascendingOrder: bool) -> None
Sort the file entries by name, in ascending or descending order
C++: mrpt::system::CDirectoryExplorer::sortByName(class std::deque<struct mrpt::system::CDirectoryExplorer::TFileInfo> &, bool) --> void
Data and other attributes defined here:
- TFileInfo = <class 'mrpt.pymrpt.mrpt.system.CDirectoryExplorer.TFileInfo'>
- This represents the information about each file.
Static methods inherited from pybind11_builtins.pybind11_object:
- __new__(*args, **kwargs) from pybind11_builtins.pybind11_type
- Create and return a new object. See help(type) for accurate signature.
|
class CObserver(pybind11_builtins.pybind11_object) |
|
Inherit from this class to get notified about events from any CObservable
object after subscribing to it.
The main methods in this class are:
- observeBegin(): To be called to start listening at a given object.
- OnEvent(): Virtual functions to be implemented in your child class to
receive all the notifications.
Note that if custom (child) mrptEvent classes are used, you can tell
between them in runtime with "dynamic_cast<>()".
The pairs CObservable / CObserver automatically notify each other the
destruction of any of them, effectively ending the subscription of events.
CObservable, mrptEvent |
|
- Method resolution order:
- CObserver
- pybind11_builtins.pybind11_object
- builtins.object
Methods defined here:
- __init__(...)
- __init__(*args, **kwargs)
Overloaded function.
1. __init__(self: mrpt.pymrpt.mrpt.system.CObserver) -> None
2. __init__(self: mrpt.pymrpt.mrpt.system.CObserver, arg0: mrpt.pymrpt.mrpt.system.CObserver) -> None
- assign(...)
- assign(self: mrpt.pymrpt.mrpt.system.CObserver, : mrpt.pymrpt.mrpt.system.CObserver) -> mrpt.pymrpt.mrpt.system.CObserver
C++: mrpt::system::CObserver::operator=(const class mrpt::system::CObserver &) --> class mrpt::system::CObserver &
- observeBegin(...)
- observeBegin(self: mrpt.pymrpt.mrpt.system.CObserver, obj: mrpt.pymrpt.mrpt.system.CObservable) -> None
Starts the subscription of this observer to the given object.
observeEnd
C++: mrpt::system::CObserver::observeBegin(class mrpt::system::CObservable &) --> void
- observeEnd(...)
- observeEnd(self: mrpt.pymrpt.mrpt.system.CObserver, obj: mrpt.pymrpt.mrpt.system.CObservable) -> None
Ends the subscription of this observer to the given object (note that
there is no need to call this method, since the destruction of the first
of observer/observed will put an end to the process
observeBegin
C++: mrpt::system::CObserver::observeEnd(class mrpt::system::CObservable &) --> void
Static methods inherited from pybind11_builtins.pybind11_object:
- __new__(*args, **kwargs) from pybind11_builtins.pybind11_type
- Create and return a new object. See help(type) for accurate signature.
|
class COutputLoggerStreamWrapper(pybind11_builtins.pybind11_object) |
|
For use in MRPT_LOG_DEBUG_STREAM(), etc. |
|
- Method resolution order:
- COutputLoggerStreamWrapper
- pybind11_builtins.pybind11_object
- builtins.object
Methods defined here:
- __init__(self, /, *args, **kwargs)
- Initialize self. See help(type(self)) for accurate signature.
Static methods inherited from pybind11_builtins.pybind11_object:
- __new__(*args, **kwargs) from pybind11_builtins.pybind11_type
- Create and return a new object. See help(type) for accurate signature.
|
class CRateTimer(pybind11_builtins.pybind11_object) |
|
A class for calling sleep() in a loop, such that the amount of sleep time
will be computed to make the loop run at the desired rate (in Hz). |
|
- Method resolution order:
- CRateTimer
- pybind11_builtins.pybind11_object
- builtins.object
Methods defined here:
- __init__(...)
- __init__(*args, **kwargs)
Overloaded function.
1. __init__(self: mrpt.pymrpt.mrpt.system.CRateTimer) -> None
doc
2. __init__(self: mrpt.pymrpt.mrpt.system.CRateTimer, rate_hz: float) -> None
3. __init__(self: mrpt.pymrpt.mrpt.system.CRateTimer, arg0: mrpt.pymrpt.mrpt.system.CRateTimer) -> None
- assign(...)
- assign(self: mrpt.pymrpt.mrpt.system.CRateTimer, : mrpt.pymrpt.mrpt.system.CRateTimer) -> mrpt.pymrpt.mrpt.system.CRateTimer
C++: mrpt::system::CRateTimer::operator=(const class mrpt::system::CRateTimer &) --> class mrpt::system::CRateTimer &
- rate(...)
- rate(self: mrpt.pymrpt.mrpt.system.CRateTimer) -> float
Gets current rate (Hz)
C++: mrpt::system::CRateTimer::rate() const --> double
- setRate(...)
- setRate(self: mrpt.pymrpt.mrpt.system.CRateTimer, rate_hz: float) -> None
Changes the object loop rate (Hz)
C++: mrpt::system::CRateTimer::setRate(const double) --> void
- sleep(...)
- sleep(self: mrpt.pymrpt.mrpt.system.CRateTimer) -> bool
Sleeps for some time, such as the return of this method is 1/rate
(seconds)
after the return of the previous call.
false if the rate could not be achieved ("we are already late"),
true if all went right.
C++: mrpt::system::CRateTimer::sleep() --> bool
Static methods inherited from pybind11_builtins.pybind11_object:
- __new__(*args, **kwargs) from pybind11_builtins.pybind11_type
- Create and return a new object. See help(type) for accurate signature.
|
class CTicTac(pybind11_builtins.pybind11_object) |
|
A high-performance stopwatch, with typical resolution of nanoseconds.
This always uses the system MONOTONIC clock, despite the setting in
mrpt::Clock.
The class is named after the Spanish equivalent of "Tic-Toc" ;-) |
|
- Method resolution order:
- CTicTac
- pybind11_builtins.pybind11_object
- builtins.object
Methods defined here:
- Tac(...)
- Tac(self: mrpt.pymrpt.mrpt.system.CTicTac) -> float
Stops the stopwatch.
Returns the ellapsed time in seconds.
Tic()
C++: mrpt::system::CTicTac::Tac() const --> double
- Tic(...)
- Tic(self: mrpt.pymrpt.mrpt.system.CTicTac) -> None
Starts the stopwatch.
Tac()
C++: mrpt::system::CTicTac::Tic() --> void
- __init__(...)
- __init__(*args, **kwargs)
Overloaded function.
1. __init__(self: mrpt.pymrpt.mrpt.system.CTicTac) -> None
2. __init__(self: mrpt.pymrpt.mrpt.system.CTicTac, arg0: mrpt.pymrpt.mrpt.system.CTicTac) -> None
- assign(...)
- assign(self: mrpt.pymrpt.mrpt.system.CTicTac, : mrpt.pymrpt.mrpt.system.CTicTac) -> mrpt.pymrpt.mrpt.system.CTicTac
C++: mrpt::system::CTicTac::operator=(const class mrpt::system::CTicTac &) --> class mrpt::system::CTicTac &
Static methods inherited from pybind11_builtins.pybind11_object:
- __new__(*args, **kwargs) from pybind11_builtins.pybind11_type
- Create and return a new object. See help(type) for accurate signature.
|
class CTimeLogger(pybind11_builtins.pybind11_object) |
|
A versatile "profiler" that logs the time spent within each pair of calls to
enter(X)-leave(X), among other stats.
The results can be dumped to cout or to Visual Studio's output panel.
This class can be also used to monitorize min/mean/max/total stats of any
user-provided parameters via the method CTimeLogger::registerUserMeasure().
Optional recording of **all** data can be enabled via
enableKeepWholeHistory() (use with caution!).
Cost of the profiler itself (measured on MSVC2015, Windows 10, Intel i5-2310
2.9GHz):
- `enter()`: average 445 ns
- `leave()`: average 316 ns
Recursive methods are supported with no problems, that is, calling "enter(X)
enter(X) ... leave(X) leave(X)".
`enter()`/`leave()` are thread-safe, in the sense of they being safe to be
called from different threads. However, calling `enter()`/`leave()` for the
same user-supplied "section name", from different threads, is not allowed. In
the latter case (and, actually, in general since it's safer against
exceptions), use the RAII helper class CTimeLoggerEntry.
CTimeLoggerEntry
The default behavior is dumping all the information at destruction. |
|
- Method resolution order:
- CTimeLogger
- pybind11_builtins.pybind11_object
- builtins.object
Methods defined here:
- __init__(...)
- __init__(*args, **kwargs)
Overloaded function.
1. __init__(self: mrpt.pymrpt.mrpt.system.CTimeLogger) -> None
doc
2. __init__(self: mrpt.pymrpt.mrpt.system.CTimeLogger, enabled: bool) -> None
doc
3. __init__(self: mrpt.pymrpt.mrpt.system.CTimeLogger, enabled: bool, name: str) -> None
doc
4. __init__(self: mrpt.pymrpt.mrpt.system.CTimeLogger, enabled: bool, name: str, keep_whole_history: bool) -> None
5. __init__(self: mrpt.pymrpt.mrpt.system.CTimeLogger, arg0: mrpt.pymrpt.mrpt.system.CTimeLogger) -> None
- assign(...)
- assign(self: mrpt.pymrpt.mrpt.system.CTimeLogger, o: mrpt.pymrpt.mrpt.system.CTimeLogger) -> mrpt.pymrpt.mrpt.system.CTimeLogger
C++: mrpt::system::CTimeLogger::operator=(const class mrpt::system::CTimeLogger &) --> class mrpt::system::CTimeLogger &
- clear(...)
- clear(*args, **kwargs)
Overloaded function.
1. clear(self: mrpt.pymrpt.mrpt.system.CTimeLogger) -> None
2. clear(self: mrpt.pymrpt.mrpt.system.CTimeLogger, deep_clear: bool) -> None
Resets all stats. By default (deep_clear=false), all section names are
remembered (not freed) so the cost of creating upon the first next call
is avoided.
By design, calling this method is the only one which is not thread
safe. It's not made thread-safe to save the performance cost. Please,
ensure that you call `clear()` only while there are no other threads
registering annotations in the object.
C++: mrpt::system::CTimeLogger::clear(bool) --> void
- disable(...)
- disable(self: mrpt.pymrpt.mrpt.system.CTimeLogger) -> None
C++: mrpt::system::CTimeLogger::disable() --> void
- dumpAllStats(...)
- dumpAllStats(*args, **kwargs)
Overloaded function.
1. dumpAllStats(self: mrpt.pymrpt.mrpt.system.CTimeLogger) -> None
2. dumpAllStats(self: mrpt.pymrpt.mrpt.system.CTimeLogger, column_width: int) -> None
Dump all stats through the COutputLogger interface.
getStatsAsText,
saveToCVSFile
C++: mrpt::system::CTimeLogger::dumpAllStats(size_t) const --> void
- enable(...)
- enable(*args, **kwargs)
Overloaded function.
1. enable(self: mrpt.pymrpt.mrpt.system.CTimeLogger) -> None
2. enable(self: mrpt.pymrpt.mrpt.system.CTimeLogger, enabled: bool) -> None
C++: mrpt::system::CTimeLogger::enable(bool) --> void
- enableKeepWholeHistory(...)
- enableKeepWholeHistory(*args, **kwargs)
Overloaded function.
1. enableKeepWholeHistory(self: mrpt.pymrpt.mrpt.system.CTimeLogger) -> None
2. enableKeepWholeHistory(self: mrpt.pymrpt.mrpt.system.CTimeLogger, enable: bool) -> None
C++: mrpt::system::CTimeLogger::enableKeepWholeHistory(bool) --> void
- getLastTime(...)
- getLastTime(self: mrpt.pymrpt.mrpt.system.CTimeLogger, name: str) -> float
Return the last execution time of the given "section", or 0 if it hasn't
ever been called "enter" with that section name
C++: mrpt::system::CTimeLogger::getLastTime(const std::string &) const --> double
- getMeanTime(...)
- getMeanTime(self: mrpt.pymrpt.mrpt.system.CTimeLogger, name: str) -> float
Return the mean execution time of the given "section", or 0 if it hasn't
ever been called "enter" with that section name
C++: mrpt::system::CTimeLogger::getMeanTime(const std::string &) const --> double
- getName(...)
- getName(self: mrpt.pymrpt.mrpt.system.CTimeLogger) -> str
C++: mrpt::system::CTimeLogger::getName() const --> const std::string &
- getStatsAsText(...)
- getStatsAsText(*args, **kwargs)
Overloaded function.
1. getStatsAsText(self: mrpt.pymrpt.mrpt.system.CTimeLogger) -> str
2. getStatsAsText(self: mrpt.pymrpt.mrpt.system.CTimeLogger, column_width: int) -> str
Dump all stats to a multi-line text string.
dumpAllStats,
saveToCVSFile
C++: mrpt::system::CTimeLogger::getStatsAsText(size_t) const --> std::string
- isEnabled(...)
- isEnabled(self: mrpt.pymrpt.mrpt.system.CTimeLogger) -> bool
C++: mrpt::system::CTimeLogger::isEnabled() const --> bool
- isEnabledKeepWholeHistory(...)
- isEnabledKeepWholeHistory(self: mrpt.pymrpt.mrpt.system.CTimeLogger) -> bool
C++: mrpt::system::CTimeLogger::isEnabledKeepWholeHistory() const --> bool
- saveToCSVFile(...)
- saveToCSVFile(self: mrpt.pymrpt.mrpt.system.CTimeLogger, csv_file: str) -> None
Dump all stats to a Comma Separated Values (CSV) file.
dumpAllStats
C++: mrpt::system::CTimeLogger::saveToCSVFile(const std::string &) const --> void
- saveToMFile(...)
- saveToMFile(self: mrpt.pymrpt.mrpt.system.CTimeLogger, m_file: str) -> None
Dump all stats to a Matlab/Octave (.m) file.
dumpAllStats
C++: mrpt::system::CTimeLogger::saveToMFile(const std::string &) const --> void
- setName(...)
- setName(self: mrpt.pymrpt.mrpt.system.CTimeLogger, name: str) -> None
C++: mrpt::system::CTimeLogger::setName(const std::string &) --> void
Data and other attributes defined here:
- TCallStats = <class 'mrpt.pymrpt.mrpt.system.CTimeLogger.TCallStats'>
- Data of each call section: # of calls, minimum, maximum, average and
overall execution time (in seconds)
getStats
Static methods inherited from pybind11_builtins.pybind11_object:
- __new__(*args, **kwargs) from pybind11_builtins.pybind11_type
- Create and return a new object. See help(type) for accurate signature.
|
class CTimeLoggerEntry(pybind11_builtins.pybind11_object) |
|
A safe way to call enter() and leave() of a mrpt::system::CTimeLogger upon
construction and destruction of
this auxiliary object, making sure that leave() will be called upon
exceptions, etc.
Usage mode #1 (scoped):
Usage mode #2 (unscoped): |
|
- Method resolution order:
- CTimeLoggerEntry
- pybind11_builtins.pybind11_object
- builtins.object
Methods defined here:
- __init__(...)
- __init__(self: mrpt.pymrpt.mrpt.system.CTimeLoggerEntry, arg0: mrpt.pymrpt.mrpt.system.CTimeLoggerEntry) -> None
- stop(...)
- stop(self: mrpt.pymrpt.mrpt.system.CTimeLoggerEntry) -> None
C++: mrpt::system::CTimeLoggerEntry::stop() --> void
Static methods inherited from pybind11_builtins.pybind11_object:
- __new__(*args, **kwargs) from pybind11_builtins.pybind11_type
- Create and return a new object. See help(type) for accurate signature.
|
class CTimeLoggerSaveAtDtor(pybind11_builtins.pybind11_object) |
|
A helper class to save CSV stats upon self destruction, for example, at the
end of a program run. The target file will be named after timelogger's name. |
|
- Method resolution order:
- CTimeLoggerSaveAtDtor
- pybind11_builtins.pybind11_object
- builtins.object
Methods defined here:
- __init__(...)
- __init__(self: mrpt.pymrpt.mrpt.system.CTimeLoggerSaveAtDtor, tm: mrpt.pymrpt.mrpt.system.CTimeLogger) -> None
Static methods inherited from pybind11_builtins.pybind11_object:
- __new__(*args, **kwargs) from pybind11_builtins.pybind11_type
- Create and return a new object. See help(type) for accurate signature.
|
class ConsoleBackgroundColor(pybind11_builtins.pybind11_object) |
| |
- Method resolution order:
- ConsoleBackgroundColor
- pybind11_builtins.pybind11_object
- builtins.object
Methods defined here:
- __eq__(...)
- __eq__(self: object, other: object) -> bool
- __getstate__(...)
- __getstate__(self: object) -> int
- __hash__(...)
- __hash__(self: object) -> int
- __index__(...)
- __index__(self: mrpt.pymrpt.mrpt.system.ConsoleBackgroundColor) -> int
- __init__(...)
- __init__(self: mrpt.pymrpt.mrpt.system.ConsoleBackgroundColor, value: int) -> None
- __int__(...)
- __int__(self: mrpt.pymrpt.mrpt.system.ConsoleBackgroundColor) -> int
- __ne__(...)
- __ne__(self: object, other: object) -> bool
- __repr__(...)
- __repr__(self: object) -> str
- __setstate__(...)
- __setstate__(self: mrpt.pymrpt.mrpt.system.ConsoleBackgroundColor, state: int) -> None
- __str__ = name(...)
- name(self: handle) -> str
Readonly properties defined here:
- __members__
- name
- name(self: handle) -> str
- value
Data and other attributes defined here:
- BLACK = <ConsoleBackgroundColor.BLACK: 40>
- BLUE = <ConsoleBackgroundColor.BLUE: 44>
- BRIGHT_BLACK = <ConsoleBackgroundColor.BRIGHT_BLACK: 100>
- BRIGHT_BLUE = <ConsoleBackgroundColor.BRIGHT_BLUE: 104>
- BRIGHT_CYAN = <ConsoleBackgroundColor.BRIGHT_CYAN: 106>
- BRIGHT_GREEN = <ConsoleBackgroundColor.BRIGHT_GREEN: 102>
- BRIGHT_MAGENTA = <ConsoleBackgroundColor.BRIGHT_MAGENTA: 105>
- BRIGHT_RED = <ConsoleBackgroundColor.BRIGHT_RED: 101>
- BRIGHT_WHITE = <ConsoleBackgroundColor.BRIGHT_WHITE: 107>
- BRIGHT_YELLOW = <ConsoleBackgroundColor.BRIGHT_YELLOW: 103>
- CYAN = <ConsoleBackgroundColor.CYAN: 46>
- DEFAULT = <ConsoleBackgroundColor.DEFAULT: 0>
- GREEN = <ConsoleBackgroundColor.GREEN: 42>
- MAGENTA = <ConsoleBackgroundColor.MAGENTA: 45>
- RED = <ConsoleBackgroundColor.RED: 41>
- WHITE = <ConsoleBackgroundColor.WHITE: 34>
- YELLOW = <ConsoleBackgroundColor.YELLOW: 43>
Static methods inherited from pybind11_builtins.pybind11_object:
- __new__(*args, **kwargs) from pybind11_builtins.pybind11_type
- Create and return a new object. See help(type) for accurate signature.
|
class ConsoleForegroundColor(pybind11_builtins.pybind11_object) |
| |
- Method resolution order:
- ConsoleForegroundColor
- pybind11_builtins.pybind11_object
- builtins.object
Methods defined here:
- __eq__(...)
- __eq__(self: object, other: object) -> bool
- __getstate__(...)
- __getstate__(self: object) -> int
- __hash__(...)
- __hash__(self: object) -> int
- __index__(...)
- __index__(self: mrpt.pymrpt.mrpt.system.ConsoleForegroundColor) -> int
- __init__(...)
- __init__(self: mrpt.pymrpt.mrpt.system.ConsoleForegroundColor, value: int) -> None
- __int__(...)
- __int__(self: mrpt.pymrpt.mrpt.system.ConsoleForegroundColor) -> int
- __ne__(...)
- __ne__(self: object, other: object) -> bool
- __repr__(...)
- __repr__(self: object) -> str
- __setstate__(...)
- __setstate__(self: mrpt.pymrpt.mrpt.system.ConsoleForegroundColor, state: int) -> None
- __str__ = name(...)
- name(self: handle) -> str
Readonly properties defined here:
- __members__
- name
- name(self: handle) -> str
- value
Data and other attributes defined here:
- BLACK = <ConsoleForegroundColor.BLACK: 30>
- BLUE = <ConsoleForegroundColor.BLUE: 34>
- BRIGHT_BLACK = <ConsoleForegroundColor.BRIGHT_BLACK: 90>
- BRIGHT_BLUE = <ConsoleForegroundColor.BRIGHT_BLUE: 94>
- BRIGHT_CYAN = <ConsoleForegroundColor.BRIGHT_CYAN: 96>
- BRIGHT_GREEN = <ConsoleForegroundColor.BRIGHT_GREEN: 92>
- BRIGHT_MAGENTA = <ConsoleForegroundColor.BRIGHT_MAGENTA: 95>
- BRIGHT_RED = <ConsoleForegroundColor.BRIGHT_RED: 91>
- BRIGHT_WHITE = <ConsoleForegroundColor.BRIGHT_WHITE: 97>
- BRIGHT_YELLOW = <ConsoleForegroundColor.BRIGHT_YELLOW: 93>
- CYAN = <ConsoleForegroundColor.CYAN: 36>
- DEFAULT = <ConsoleForegroundColor.DEFAULT: 0>
- GREEN = <ConsoleForegroundColor.GREEN: 32>
- MAGENTA = <ConsoleForegroundColor.MAGENTA: 35>
- RED = <ConsoleForegroundColor.RED: 31>
- WHITE = <ConsoleForegroundColor.WHITE: 37>
- YELLOW = <ConsoleForegroundColor.YELLOW: 33>
Static methods inherited from pybind11_builtins.pybind11_object:
- __new__(*args, **kwargs) from pybind11_builtins.pybind11_type
- Create and return a new object. See help(type) for accurate signature.
|
class ConsoleTextStyle(pybind11_builtins.pybind11_object) |
| |
- Method resolution order:
- ConsoleTextStyle
- pybind11_builtins.pybind11_object
- builtins.object
Methods defined here:
- __eq__(...)
- __eq__(self: object, other: object) -> bool
- __getstate__(...)
- __getstate__(self: object) -> int
- __hash__(...)
- __hash__(self: object) -> int
- __index__(...)
- __index__(self: mrpt.pymrpt.mrpt.system.ConsoleTextStyle) -> int
- __init__(...)
- __init__(self: mrpt.pymrpt.mrpt.system.ConsoleTextStyle, value: int) -> None
- __int__(...)
- __int__(self: mrpt.pymrpt.mrpt.system.ConsoleTextStyle) -> int
- __ne__(...)
- __ne__(self: object, other: object) -> bool
- __repr__(...)
- __repr__(self: object) -> str
- __setstate__(...)
- __setstate__(self: mrpt.pymrpt.mrpt.system.ConsoleTextStyle, state: int) -> None
- __str__ = name(...)
- name(self: handle) -> str
Readonly properties defined here:
- __members__
- name
- name(self: handle) -> str
- value
Data and other attributes defined here:
- BLINKING = <ConsoleTextStyle.BLINKING: 5>
- BOLD = <ConsoleTextStyle.BOLD: 1>
- DIM = <ConsoleTextStyle.DIM: 2>
- INVISIBLE = <ConsoleTextStyle.INVISIBLE: 8>
- ITALIC = <ConsoleTextStyle.ITALIC: 3>
- REGULAR = <ConsoleTextStyle.REGULAR: 0>
- REVERSE = <ConsoleTextStyle.REVERSE: 7>
- UNDERLINED = <ConsoleTextStyle.UNDERLINED: 4>
Static methods inherited from pybind11_builtins.pybind11_object:
- __new__(*args, **kwargs) from pybind11_builtins.pybind11_type
- Create and return a new object. See help(type) for accurate signature.
|
class TProcessPriority(pybind11_builtins.pybind11_object) |
| |
- Method resolution order:
- TProcessPriority
- pybind11_builtins.pybind11_object
- builtins.object
Methods defined here:
- __and__(...)
- __and__(self: object, other: object) -> object
- __eq__(...)
- __eq__(self: object, other: object) -> bool
- __ge__(...)
- __ge__(self: object, other: object) -> bool
- __getstate__(...)
- __getstate__(self: object) -> int
- __gt__(...)
- __gt__(self: object, other: object) -> bool
- __hash__(...)
- __hash__(self: object) -> int
- __index__(...)
- __index__(self: mrpt.pymrpt.mrpt.system.TProcessPriority) -> int
- __init__(...)
- __init__(self: mrpt.pymrpt.mrpt.system.TProcessPriority, value: int) -> None
- __int__(...)
- __int__(self: mrpt.pymrpt.mrpt.system.TProcessPriority) -> int
- __invert__(...)
- __invert__(self: object) -> object
- __le__(...)
- __le__(self: object, other: object) -> bool
- __lt__(...)
- __lt__(self: object, other: object) -> bool
- __ne__(...)
- __ne__(self: object, other: object) -> bool
- __or__(...)
- __or__(self: object, other: object) -> object
- __rand__(...)
- __rand__(self: object, other: object) -> object
- __repr__(...)
- __repr__(self: object) -> str
- __ror__(...)
- __ror__(self: object, other: object) -> object
- __rxor__(...)
- __rxor__(self: object, other: object) -> object
- __setstate__(...)
- __setstate__(self: mrpt.pymrpt.mrpt.system.TProcessPriority, state: int) -> None
- __str__ = name(...)
- name(self: handle) -> str
- __xor__(...)
- __xor__(self: object, other: object) -> object
Readonly properties defined here:
- __members__
- name
- name(self: handle) -> str
- value
Data and other attributes defined here:
- ppHigh = <TProcessPriority.ppHigh: 2>
- ppIdle = <TProcessPriority.ppIdle: 0>
- ppNormal = <TProcessPriority.ppNormal: 1>
- ppVeryHigh = <TProcessPriority.ppVeryHigh: 3>
Static methods inherited from pybind11_builtins.pybind11_object:
- __new__(*args, **kwargs) from pybind11_builtins.pybind11_type
- Create and return a new object. See help(type) for accurate signature.
|
class TThreadPriority(pybind11_builtins.pybind11_object) |
| |
- Method resolution order:
- TThreadPriority
- pybind11_builtins.pybind11_object
- builtins.object
Methods defined here:
- __and__(...)
- __and__(self: object, other: object) -> object
- __eq__(...)
- __eq__(self: object, other: object) -> bool
- __ge__(...)
- __ge__(self: object, other: object) -> bool
- __getstate__(...)
- __getstate__(self: object) -> int
- __gt__(...)
- __gt__(self: object, other: object) -> bool
- __hash__(...)
- __hash__(self: object) -> int
- __index__(...)
- __index__(self: mrpt.pymrpt.mrpt.system.TThreadPriority) -> int
- __init__(...)
- __init__(self: mrpt.pymrpt.mrpt.system.TThreadPriority, value: int) -> None
- __int__(...)
- __int__(self: mrpt.pymrpt.mrpt.system.TThreadPriority) -> int
- __invert__(...)
- __invert__(self: object) -> object
- __le__(...)
- __le__(self: object, other: object) -> bool
- __lt__(...)
- __lt__(self: object, other: object) -> bool
- __ne__(...)
- __ne__(self: object, other: object) -> bool
- __or__(...)
- __or__(self: object, other: object) -> object
- __rand__(...)
- __rand__(self: object, other: object) -> object
- __repr__(...)
- __repr__(self: object) -> str
- __ror__(...)
- __ror__(self: object, other: object) -> object
- __rxor__(...)
- __rxor__(self: object, other: object) -> object
- __setstate__(...)
- __setstate__(self: mrpt.pymrpt.mrpt.system.TThreadPriority, state: int) -> None
- __str__ = name(...)
- name(self: handle) -> str
- __xor__(...)
- __xor__(self: object, other: object) -> object
Readonly properties defined here:
- __members__
- name
- name(self: handle) -> str
- value
Data and other attributes defined here:
- tpHigh = <TThreadPriority.tpHigh: 1>
- tpHigher = <TThreadPriority.tpHigher: 2>
- tpHighest = <TThreadPriority.tpHighest: 15>
- tpLow = <TThreadPriority.tpLow: -1>
- tpLower = <TThreadPriority.tpLower: -2>
- tpLowests = <TThreadPriority.tpLowests: -15>
- tpNormal = <TThreadPriority.tpNormal: 0>
Static methods inherited from pybind11_builtins.pybind11_object:
- __new__(*args, **kwargs) from pybind11_builtins.pybind11_type
- Create and return a new object. See help(type) for accurate signature.
|
class TTimeParts(pybind11_builtins.pybind11_object) |
|
The parts of a date/time, like the standard `tm` but with fractional
(`double`) seconds.
TTimeStamp, timestampToParts, buildTimestampFromParts |
|
- Method resolution order:
- TTimeParts
- pybind11_builtins.pybind11_object
- builtins.object
Methods defined here:
- __init__(...)
- __init__(self: mrpt.pymrpt.mrpt.system.TTimeParts) -> None
Data descriptors defined here:
- day
- day_of_week
- daylight_saving
- hour
- minute
- month
- second
- year
Static methods inherited from pybind11_builtins.pybind11_object:
- __new__(*args, **kwargs) from pybind11_builtins.pybind11_type
- Create and return a new object. See help(type) for accurate signature.
|
class VerbosityLevel(pybind11_builtins.pybind11_object) |
| |
- Method resolution order:
- VerbosityLevel
- pybind11_builtins.pybind11_object
- builtins.object
Methods defined here:
- __and__(...)
- __and__(self: object, other: object) -> object
- __eq__(...)
- __eq__(self: object, other: object) -> bool
- __ge__(...)
- __ge__(self: object, other: object) -> bool
- __getstate__(...)
- __getstate__(self: object) -> int
- __gt__(...)
- __gt__(self: object, other: object) -> bool
- __hash__(...)
- __hash__(self: object) -> int
- __index__(...)
- __index__(self: mrpt.pymrpt.mrpt.system.VerbosityLevel) -> int
- __init__(...)
- __init__(self: mrpt.pymrpt.mrpt.system.VerbosityLevel, value: int) -> None
- __int__(...)
- __int__(self: mrpt.pymrpt.mrpt.system.VerbosityLevel) -> int
- __invert__(...)
- __invert__(self: object) -> object
- __le__(...)
- __le__(self: object, other: object) -> bool
- __lt__(...)
- __lt__(self: object, other: object) -> bool
- __ne__(...)
- __ne__(self: object, other: object) -> bool
- __or__(...)
- __or__(self: object, other: object) -> object
- __rand__(...)
- __rand__(self: object, other: object) -> object
- __repr__(...)
- __repr__(self: object) -> str
- __ror__(...)
- __ror__(self: object, other: object) -> object
- __rxor__(...)
- __rxor__(self: object, other: object) -> object
- __setstate__(...)
- __setstate__(self: mrpt.pymrpt.mrpt.system.VerbosityLevel, state: int) -> None
- __str__ = name(...)
- name(self: handle) -> str
- __xor__(...)
- __xor__(self: object, other: object) -> object
Readonly properties defined here:
- __members__
- name
- name(self: handle) -> str
- value
Data and other attributes defined here:
- LVL_DEBUG = <VerbosityLevel.LVL_DEBUG: 0>
- LVL_ERROR = <VerbosityLevel.LVL_ERROR: 3>
- LVL_INFO = <VerbosityLevel.LVL_INFO: 1>
- LVL_WARN = <VerbosityLevel.LVL_WARN: 2>
- NUMBER_OF_VERBOSITY_LEVELS = <VerbosityLevel.NUMBER_OF_VERBOSITY_LEVELS: 4>
Static methods inherited from pybind11_builtins.pybind11_object:
- __new__(*args, **kwargs) from pybind11_builtins.pybind11_type
- Create and return a new object. See help(type) for accurate signature.
|
class mrptEvent(pybind11_builtins.pybind11_object) |
|
The basic event type for the observer-observable pattern in MRPT.
You can sub-class this base class to create custom event types, then
tell between them in runtime with isOfType<T>(), for example:
CObserver, CObservable |
|
- Method resolution order:
- mrptEvent
- pybind11_builtins.pybind11_object
- builtins.object
Methods defined here:
- __init__(...)
- __init__(*args, **kwargs)
Overloaded function.
1. __init__(self: mrpt.pymrpt.mrpt.system.mrptEvent) -> None
2. __init__(self: mrpt.pymrpt.mrpt.system.mrptEvent, arg0: mrpt.pymrpt.mrpt.system.mrptEvent) -> None
3. __init__(self: mrpt.pymrpt.mrpt.system.mrptEvent, arg0: mrpt.pymrpt.mrpt.system.mrptEvent) -> None
- assign(...)
- assign(self: mrpt.pymrpt.mrpt.system.mrptEvent, : mrpt.pymrpt.mrpt.system.mrptEvent) -> mrpt.pymrpt.mrpt.system.mrptEvent
C++: mrpt::system::mrptEvent::operator=(const class mrpt::system::mrptEvent &) --> class mrpt::system::mrptEvent &
Data descriptors defined here:
- timestamp
Static methods inherited from pybind11_builtins.pybind11_object:
- __new__(*args, **kwargs) from pybind11_builtins.pybind11_type
- Create and return a new object. See help(type) for accurate signature.
|
|