Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -1,3 +1,6 @@
# AI generated files
.claude/

# Byte-compiled / optimized / DLL files
__pycache__/
*.py[cod]
Expand Down
37 changes: 35 additions & 2 deletions docs/DESIGN_AND_IMPLEMENTATION.md
Original file line number Diff line number Diff line change
Expand Up @@ -36,12 +36,14 @@ In particular, the messages follow conventions from [Isaac ROS NITROS](https://g
We provide a single node which can subscribe to arbitrary topics and produce greenwave diagnostics for them. You can think of this like a more efficient, more featureful version of ros2 topic hz. Implementation: `greenwave_monitor/src/greenwave_monitor.cpp`

- Starts a generic subscription per monitored topic.
- Reads topic list from:
- Reads topic list and parameters from:
- `gw_monitored_topics`
- `gw_time_check_preset` (see [Time check presets](#time-check-presets))
- `gw_frequency_monitored_topics.<topic>.expected_frequency`
- `gw_frequency_monitored_topics.<topic>.tolerance`
- Resolves topic type dynamically and uses serialized subscriptions.
- Extracts message timestamps for known header-bearing types.
- Extracts message timestamps for known header-bearing types (see `has_header_from_type()`).
- For topics without a header, uses node receive time; the time check preset controls which checks run.
- Publishes diagnostics once per second in `timer_callback()`.

Provides runtime services:
Expand Down Expand Up @@ -121,6 +123,37 @@ Dashboards expect specific keys inside `DiagnosticStatus.values`, including:

These are already emitted by `GreenwaveDiagnostics::publishDiagnostics()`. You can write your own publisher for greenwave compatible `/diagnostics`, but we don't guarantee schema stability for now.

## Timestamp sources

Greenwave diagnostics tracks two timestamp series for each monitored topic:

- **Header timestamp** — the `stamp` field embedded in the message's `std_msgs/Header`. For sensor data this is typically set at acquisition time (e.g. when a camera frame is captured), making it more accurate than node receive time for characterizing true source frequency and jitter.
- **Node receive time** — the wall-clock time when the ROS message callback fires, reflecting when the subscriber received the message including any network or queuing delays.

Latency (`current_delay_from_realtime_ms`) is measured as the difference between the node receive time and the header timestamp. A large value indicates significant pipeline delay between capture and consumption.

## Time check presets

The `gw_time_check_preset` node parameter controls which time-based checks run on each monitored topic. This is especially important for **headerless topics** (e.g. `std_msgs/String`), where message timestamps are not available and the monitor can optionally use node receive time instead.

| Preset value | Description |
|--------------|-------------|
| `header_with_nodetime_fallback` (default) | For header-bearing types: check message timestamp (rate, jitter, increasing). For headerless types: fall back to node time and run FPS window and increasing-timestamp checks. |
| `header_only` | Check message timestamp only. Headerless topics get no timing checks (diagnostics stay OK). Use when you only care about headered sources. |
| `nodetime_only` | Use node receive time for all topics (header and headerless). Runs FPS window and increasing-timestamp checks. |
| `none` | No time-based checks; only raw rate/latency values are computed and published. |

Configure via YAML or launch:

```yaml
greenwave_monitor:
ros__parameters:
gw_time_check_preset: header_with_nodetime_fallback # or header_only, nodetime_only, none
gw_monitored_topics: ['/my_topic']
```

Invalid values are ignored and the default `header_with_nodetime_fallback` is used (a warning is logged).

## Implementation Notes And Pitfalls

- Message timestamp should be epoch time for latency to be meaningful.
Expand Down
5 changes: 5 additions & 0 deletions greenwave_monitor/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -109,6 +109,11 @@ if(BUILD_TESTING)
WORKING_DIRECTORY ${CMAKE_SOURCE_DIR}
)

ament_add_pytest_test(test_greenwave_monitor_preset test/test_greenwave_monitor_preset.py
TIMEOUT 180
WORKING_DIRECTORY ${CMAKE_SOURCE_DIR}
)

# Add explicit linting tests
ament_add_pytest_test(test_flake8 test/test_flake8.py
TIMEOUT 60
Expand Down
6 changes: 6 additions & 0 deletions greenwave_monitor/config/example.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,12 @@

greenwave_monitor:
ros__parameters:
# gw_time_check_preset parameter specifies the time checks to perform on the topics. Options are:
# - header_with_nodetime_fallback: check the header timestamp and node time
# - header_only: check the header timestamp only
# - nodetime_only: check the node time only
# - none: do not check the time
gw_time_check_preset: header_with_nodetime_fallback
# gw_monitored_topics parameter specifies topics to monitor that do not require expected
# frequencies or tolerances.
gw_monitored_topics: ['/string_topic']
Expand Down
Loading