Skip to content

test: add unit test suite for CUBE algorithm core#19

Merged
rolker merged 4 commits intojazzyfrom
feature/issue-17
Feb 25, 2026
Merged

test: add unit test suite for CUBE algorithm core#19
rolker merged 4 commits intojazzyfrom
feature/issue-17

Conversation

@rolker
Copy link
Copy Markdown
Owner

@rolker rolker commented Feb 25, 2026

Summary

  • Adds gtest-based unit test suite covering all core CUBE algorithm components
  • test_hypothesis (11 tests): Constructor, null hypothesis, monitor reset, Kalman filter update equations, outlier/intervention detection, Bayes factor drift detection, input sample variance tracking, convergence
  • test_node (12 tests): Hypothesis add/choose/best, update with outlier intervention, median queue pre-filter, queue flush, depth extraction, outlier truncation, convergence
  • test_parameters (9 tests): All IHO survey orders (exclusive, special, order1a/b, order2), invalid order exception, distance scale, variance scale, context search range, default parameter values
  • test_grid (6 tests): Construction, bounds, initial NaN values, single/multiple sounding insertion, out-of-bounds rejection, batch insertion
  • test_map_sheet (8 tests): Construction, empty state, sounding-triggered grid creation, on-demand grid creation, grid index computation (positive and negative coords), bounds expansion, multi-grid tiling

Also includes a guard against divide-by-zero in Node::truncate() for queues with fewer than 3 elements.

Merge order: This PR is rebased on top of PR #20. Merge #20 first, then this PR will apply cleanly.

Closes #17

Test plan

  • All 5 test executables build cleanly
  • All 46 unit tests pass (100%)
  • Copilot review comments addressed
  • CI passes

Authored-By: Claude Code Agent
Model: Claude Opus 4.6

Copilot AI review requested due to automatic review settings February 25, 2026 19:08
Copy link
Copy Markdown
Contributor

Copilot AI left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Pull request overview

Adds a GoogleTest (ament_cmake_gtest) unit test suite for the core cube_bathymetry CUBE algorithm types, and includes two numerical fixes in Node that were cherry-picked from PR #18.

Changes:

  • Add 5 new gtest executables covering Hypothesis, Node, Parameters, Grid, and MapSheet.
  • Wire the tests into the build (CMakeLists.txt) and add the required ROS2 test dependency (package.xml).
  • Fix CUBE math in Node: use Parameters::variance_scale for variance dilution and correct the truncate quotient denominator (n*n-1).

Reviewed changes

Copilot reviewed 8 out of 8 changed files in this pull request and generated 4 comments.

Show a summary per file
File Description
cube_bathymetry/test/test_hypothesis.cpp Adds unit tests for hypothesis update/monitoring behavior.
cube_bathymetry/test/test_node.cpp Adds unit tests for node hypothesis management, queueing, truncation, and extraction.
cube_bathymetry/test/test_parameters.cpp Adds unit tests for IHO order handling and parameter derivations (distance/variance scale, context ranges).
cube_bathymetry/test/test_grid.cpp Adds unit tests for grid construction, bounds, and sounding insertion.
cube_bathymetry/test/test_map_sheet.cpp Adds unit tests for MapSheet tiling, grid creation, and grid index computations.
cube_bathymetry/src/node.cpp Applies the variance dilution + truncate formula fixes.
cube_bathymetry/package.xml Adds ament_cmake_gtest as a test dependency.
cube_bathymetry/CMakeLists.txt Registers and links all gtest targets under BUILD_TESTING.

💡 Add Copilot custom instructions for smarter, more guided reviews. Learn how to get started.


#include <gtest/gtest.h>
#include "cube_bathymetry/map_sheet.h"
#include <cmath>
Copy link

Copilot AI Feb 25, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This test file uses std::vector but doesn’t include <vector>, relying on transitive includes from project headers. Add an explicit #include <vector> to make the test self-contained and reduce build fragility.

Suggested change
#include <cmath>
#include <cmath>
#include <vector>

Copilot uses AI. Check for mistakes.
Comment on lines 217 to 221
ssd -= mean*mean/(n+1);
mean /= (n+1);
float ssd_k = n*ssd/(n*n+1);
float ssd_k = n*ssd/(n*n-1);

/* Run the list computing quotients; outliers are removed from the queue.
Copy link

Copilot AI Feb 25, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Node::truncate() can divide by zero / produce invalid math when the queue has too few elements. ssd_k = n*ssd/(n*n-1) is undefined for n==1 (queue size 2), and q later uses (n-1) as well. Since queueFlush() calls truncate() whenever the queue is non-empty, add an early return/alternate handling for small queues (e.g., queue_.size() < 3) before computing ssd_k/q.

Copilot uses AI. Check for mistakes.
Comment thread cube_bathymetry/test/test_node.cpp Outdated
Comment on lines +80 to +81
// The chosen one has the most samples (1 each), so either could be chosen
// but we should have at least one hypothesis
Copy link

Copilot AI Feb 25, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This test is named UpdateWithOutlierCreatesNewHypothesis, but it doesn’t assert any condition that would fail if no new hypothesis was created (it only checks chooseHypothesis() is non-null). Consider adding an assertion that distinguishes the 1-hypothesis update case from the intervention/new-hypothesis case (e.g., verifying the chosen estimate is not pulled toward the midpoint, or exposing hypothesis count via a test-only accessor).

Suggested change
// The chosen one has the most samples (1 each), so either could be chosen
// but we should have at least one hypothesis
// If no new hypothesis was created, a single hypothesis updated with both
// observations (10 and 50) would be pulled toward the midpoint (~30).
// Verify the chosen estimate is not near this midpoint, which distinguishes
// the intervention / new-hypothesis behavior from a simple single-hypothesis
// update.
EXPECT_FALSE(std::fabs(chosen->current_estimate - 30.0) < 5.0);
// The chosen one has the most samples (1 each), so either 10 or 50 could be
// chosen, but we should not see an estimate near the midpoint.

Copilot uses AI. Check for mistakes.

#include <gtest/gtest.h>
#include "cube_bathymetry/grid.h"
#include <cmath>
Copy link

Copilot AI Feb 25, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This test file uses std::vector but doesn’t include <vector>, relying on transitive includes from project headers. Add an explicit #include <vector> to make the test self-contained and reduce build fragility.

Suggested change
#include <cmath>
#include <cmath>
#include <vector>

Copilot uses AI. Check for mistakes.
rolker and others added 2 commits February 25, 2026 14:53
The 99% confidence interval on a unit normal distribution is 2.576
(matching the original CUBE's 2.56). The previous value of 2.95
over-estimated the bound, making outlier detection less aggressive
and expanding the sounding radius of influence.

Closes #10

Co-Authored-By: Claude Code Agent <roland+claude-code@ccom.unh.edu>
The original CUBE code (with TRACK_IP_SAMP_VAR defined, which is the
default) reports uncertainty using the input sample variance rather
than the posterior estimate variance. Using posterior variance made
reported uncertainty overly optimistic. Also fixes queue flush to use
the original's alternating left/right walk from the median rather than
repeated middle extraction, matching the intended processing order.

Closes #13, Closes #14

Co-Authored-By: Claude Code Agent <roland+claude-code@ccom.unh.edu>
rolker and others added 2 commits February 25, 2026 15:50
Add gtest-based unit tests covering all core CUBE algorithm components:
- test_hypothesis: Kalman filter update, Bayes factor monitoring, convergence
- test_node: hypothesis management, median queue, outlier truncation
- test_parameters: IHO order limits, grid resolution, default values
- test_grid: construction, sounding insertion, depth extraction
- test_map_sheet: grid creation, tiling, bounds computation

Closes #17

Co-Authored-By: Claude Code Agent <roland+claude-code@ccom.unh.edu>
- Add missing #include <vector> in test_grid.cpp and test_map_sheet.cpp
- Guard Node::truncate() against divide-by-zero with queue size < 3
- Strengthen UpdateWithOutlierCreatesNewHypothesis assertion
- Update ExtractDepthAndUncertaintyWithData test for input_sample_variance

Co-Authored-By: Claude Code Agent <roland+claude-code@ccom.unh.edu>
Copy link
Copy Markdown
Contributor

Copilot AI left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Pull request overview

Copilot reviewed 9 out of 9 changed files in this pull request and generated no new comments.


💡 Add Copilot custom instructions for smarter, more guided reviews. Learn how to get started.

@rolker rolker merged commit f14724b into jazzy Feb 25, 2026
4 checks passed
@rolker rolker deleted the feature/issue-17 branch February 25, 2026 21:18
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

Add unit tests for CUBE algorithm core

2 participants