Testing and Validation¶
Link to module repo: odom_gnss_fusion
For build instructions (including how to enable test publishers with BUILD_TESTING=ON), see the repository README.
Test Publisher¶
The package includes a test publisher that simulates both sensor inputs from a single consistent ground-truth trajectory. A body-frame base velocity is integrated into a global pose. The odometry output published on /odom_velocity adds configurable offset and noise to the body-frame velocity. The GNSS output published on /gnss_pose adds configurable noise to the global-frame ground-truth pose. The node also publishes the ground-truth global-frame velocity on /global_velocity for debugging and visualization. Furthermore, the node broadcasts a static identity TF from base_link to gnss_link.
Parameters¶
Base velocity (ground truth, body frame):
| Parameter | Type | Default | Description |
|---|---|---|---|
base_xd |
double | 1.0 | Forward velocity (m/s) |
base_yd |
double | 0.0 | Lateral velocity (m/s) |
base_phid |
double | 0.1 | Yaw rate (rad/s) |
Odometry output (/odom_velocity):
| Parameter | Type | Default | Description |
|---|---|---|---|
odom_publish_frequency_hz |
double | 1000.0 | Publication rate (Hz) |
odom_offset_xd |
double | 0.1 | Systematic X velocity offset (m/s) |
odom_offset_yd |
double | -0.05 | Systematic Y velocity offset (m/s) |
odom_offset_phid |
double | 0.01 | Systematic yaw rate offset (rad/s) |
odom_noise_stddev_xd |
double | 0.005 | X velocity noise standard deviation (m/s) |
odom_noise_stddev_yd |
double | 0.005 | Y velocity noise standard deviation (m/s) |
odom_noise_stddev_phid |
double | 0.005 | Yaw rate noise standard deviation (rad/s) |
GNSS output (/gnss_pose):
| Parameter | Type | Default | Description |
|---|---|---|---|
gnss_publish_frequency_hz |
double | 10.0 | Publication rate (Hz) |
gnss_noise_stddev_x |
double | 0.2 | X position noise standard deviation (m) |
gnss_noise_stddev_y |
double | 0.2 | Y position noise standard deviation (m) |
gnss_noise_stddev_phi |
double | 0.05 | Yaw noise standard deviation (rad) |
gnss_stale |
bool | false | Whether to publish GNSS data or not |
Frame IDs:
| Parameter | Type | Default | Description |
|---|---|---|---|
map_frame_id |
string | "map" | Header frame ID for GNSS pose |
gnss_frame_id |
string | "gnss_link" | GNSS sensor frame for static TF |
base_link_frame_id |
string | "base_link" | Robot base frame for static TF |
Note
For real deployments where the GNSS antenna is not at the robot center, broadcast the actual transform instead of using the test publisher's identity TF:
Validation Procedures¶
Noise Filtering¶
- Start the test publisher with high GNSS noise and low odometry noise:
- Set \(\tau = 1.0\) (aggressive filtering).
- Record both
/gnss_poseand/observed_pose(e.g. withros2 bag record). - Verify the observed output is significantly smoother than the raw GNSS input.
Odometry Bias Correction¶
- Start the test publisher with a systematic odometry offset:
- Set \(\tau = 0.3\).
- Verify the observed pose tracks the GNSS trajectory rather than diverging with the biased odometry.