◆ Profiler() [1/2]
mrs_lib::Profiler::Profiler |
( |
ros::NodeHandle & |
nh, |
|
|
std::string |
node_name, |
|
|
bool |
profiler_enabled |
|
) |
| |
the full constructor
- Parameters
-
nh | node handle |
node_name | the node name |
profiler_enabled | if profiling is enabled |
◆ Profiler() [2/2]
mrs_lib::Profiler::Profiler |
( |
const Profiler & |
other | ) |
|
the copy constructor
- Parameters
-
◆ createRoutine() [1/2]
Routine mrs_lib::Profiler::createRoutine |
( |
std::string |
name | ) |
|
create a routine for an aperiodic function
- Parameters
-
- Returns
- the Routine
◆ createRoutine() [2/2]
Routine mrs_lib::Profiler::createRoutine |
( |
std::string |
name, |
|
|
double |
expected_rate, |
|
|
double |
threshold, |
|
|
ros::TimerEvent |
event |
|
) |
| |
create a routine for a periodic function
- Parameters
-
name | the function name |
expected_rate | the expected rate in Hz |
threshold | the delay threshold to mark it as "late" in s |
event | the ros Timer event |
- Returns
- the Routine
◆ operator=()
the assignment operator
- Parameters
-
- Returns
- this object
The documentation for this class was generated from the following files:
- include/mrs_lib/profiler.h
- src/profiler/profiler.cpp