robot_time/WALLTIMER_USAGE.md

257 lines
7.5 KiB
Markdown

# robot::WallTimer Usage Guide
## Overview
`robot::WallTimer` is a class similar to `ros::WallTimer` that allows you to call a callback function at a specified rate using **wall-clock time**. It creates a separate thread that periodically invokes your callback function.
**Key Difference from Timer:**
- `Timer` uses `Time` and `Duration` (can be affected by simulated time)
- `WallTimer` uses `WallTime` and `WallDuration` (always uses real wall-clock time)
This makes `WallTimer` ideal for:
- Performance monitoring and profiling
- Real-time deadlines and timeouts
- Hardware interfaces requiring precise timing
- Benchmarking and measurement
- Any task that needs to run at real-world intervals
## Basic Usage
### Simple WallTimer Example
```cpp
#include <robot/wall_timer.h>
#include <iostream>
void myCallback(const robot::WallTimerEvent& event)
{
std::cout << "WallTimer fired! Current wall time: "
<< event.current_real.toSec() << std::endl;
std::cout << "Time since last callback: "
<< event.last_duration.toSec() << " seconds" << std::endl;
}
int main()
{
// Create a timer that fires every 1 second (wall-clock time)
robot::WallTimer timer(
robot::WallDuration(1.0), // Period: 1 second
myCallback, // Callback function
false, // Not one-shot (repeats)
true // Auto-start
);
// Timer is now running...
// Do other work here
// Sleep for 5 seconds to see timer fire multiple times
robot::WallDuration(5.0).sleep();
// Stop the timer
timer.stop();
return 0;
}
```
### Using with Class Methods
```cpp
#include <robot/wall_timer.h>
class PerformanceMonitor
{
public:
void startMonitoring()
{
// Create timer with member function callback
timer_ = std::make_unique<robot::WallTimer>(
robot::WallDuration(0.5), // 2 Hz (every 0.5 seconds)
[this](const robot::WallTimerEvent& event) {
this->monitorCallback(event);
},
false, // Repeating
true // Auto-start
);
}
void monitorCallback(const robot::WallTimerEvent& event)
{
// Do periodic performance monitoring here
// This always uses real wall-clock time, not simulated time
std::cout << "Performance check at real time: "
<< event.current_real.toSec() << std::endl;
}
void stopMonitoring()
{
if (timer_)
{
timer_->stop();
}
}
private:
std::unique_ptr<robot::WallTimer> timer_;
};
```
### One-Shot WallTimer
```cpp
#include <robot/wall_timer.h>
void delayedAction(const robot::WallTimerEvent& event)
{
std::cout << "Delayed action executed after 5 seconds (real time)" << std::endl;
}
int main()
{
// Create a one-shot timer that fires once after 5 seconds (wall-clock)
robot::WallTimer timer(
robot::WallDuration(5.0), // Wait 5 seconds
delayedAction, // Callback
true, // One-shot
true // Auto-start
);
// Wait for timer to fire
robot::WallDuration(6.0).sleep();
return 0;
}
```
## WallTimerEvent Structure
The `WallTimerEvent` structure passed to your callback contains:
- `current_real`: The actual wall-clock time when the callback was called
- `current_expected`: The expected wall-clock time when the callback should have been called
- `last_real`: The actual wall-clock time of the previous callback
- `last_expected`: The expected wall-clock time of the previous callback
- `last_duration`: The wall-clock duration between the last two callbacks
All times are in wall-clock time (real time), not simulated time.
## API Reference
### Constructor
```cpp
WallTimer(const WallDuration& period,
const Callback& callback,
bool oneshot = false,
bool autostart = true);
```
- `period`: Time between callbacks (wall-clock duration)
- `callback`: Function to call (signature: `void(const WallTimerEvent&)`)
- `oneshot`: If true, timer fires only once
- `autostart`: If true, timer starts automatically
### Methods
- `void start()`: Start the timer. Does nothing if already started.
- `void stop()`: Stop the timer. Once this returns, no more callbacks will be called.
- `void setPeriod(const WallDuration& period, bool reset = true)`: Set the timer period. If `reset` is true, timer ignores elapsed time and next callback occurs at now()+period.
- `bool hasStarted()`: Check if timer is running
- `bool isValid()`: Check if timer has a valid callback
- `bool hasPending()`: Check if timer has any pending events to call
- `bool isOneShot()`: Check if timer is one-shot
- `void setOneShot(bool oneshot)`: Set one-shot mode
- `WallDuration getPeriod()`: Get the timer period
### Operators
- `operator void*()`: Conversion to bool (for checking validity)
- `operator==(const WallTimer&)`: Equality comparison
- `operator!=(const WallTimer&)`: Inequality comparison
- `operator<(const WallTimer&)`: Less-than comparison (for ordering in containers)
## Comparison: Timer vs WallTimer
| Feature | `Timer` | `WallTimer` |
|---------|---------|-------------|
| Time Type | `Time` / `Duration` | `WallTime` / `WallDuration` |
| Simulated Time | Can be affected | Never affected |
| Use Case | ROS message timestamps, simulation | Performance, real-time, hardware |
| Initialization | Requires `Time::init()` | No initialization needed |
| Exception | Can throw if time not initialized | Never throws |
## Example: Performance Profiling
```cpp
#include <robot/wall_timer.h>
class Profiler
{
public:
void startProfiling()
{
profile_timer_ = std::make_unique<robot::WallTimer>(
robot::WallDuration(1.0), // Profile every 1 second
[this](const robot::WallTimerEvent& event) {
this->profileCallback(event);
},
false, // Repeating
true // Auto-start
);
}
void profileCallback(const robot::WallTimerEvent& event)
{
// Measure actual wall-clock time between callbacks
double actual_interval = event.last_duration.toSec();
double expected_interval = 1.0;
if (actual_interval > expected_interval * 1.1) // 10% tolerance
{
std::cout << "WARNING: Timer drift detected! "
<< "Expected: " << expected_interval
<< "s, Actual: " << actual_interval << "s" << std::endl;
}
}
private:
std::unique_ptr<robot::WallTimer> profile_timer_;
};
```
## Example: Dynamic Period Adjustment
```cpp
#include <robot/wall_timer.h>
robot::WallTimer timer(robot::WallDuration(1.0), myCallback);
// Later, change the period
timer.setPeriod(robot::WallDuration(0.5), true); // Reset to 0.5s, reset timer
// Or change without reset
timer.setPeriod(robot::WallDuration(2.0), false); // Change to 2s, don't reset
```
## Best Practices
1. **Use WallTimer for real-time operations**: When you need precise wall-clock timing
2. **Use Timer for ROS messages**: When working with ROS messages that use simulated time
3. **Always stop timers**: Make sure to call `stop()` before destroying the timer
4. **Handle exceptions in callbacks**: Exceptions in callbacks are caught to prevent timer thread crashes
5. **Check validity**: Use `isValid()` or `operator void*()` to check if timer has a callback
## Thread Safety
`WallTimer` is thread-safe:
- Multiple threads can safely call `start()`, `stop()`, `setPeriod()`, etc.
- The callback is executed in a separate thread
- All internal state is protected by mutexes
## References
- [ROS WallTimer Documentation](http://docs.ros.org/en/indigo/api/roscpp/html/classros_1_1WallTimer.html)
- `TIMER_USAGE.md` - Guide for `robot::Timer` (uses simulated time)
- `WALLTIME_USAGE.md` - Guide for `WallTime` and `WallDuration`