Skip to content

Panav/feat/update mppi visualization#5975

Closed
Pana1v wants to merge 16 commits intoros-navigation:mainfrom
Pana1v:panav/feat/update-mppi-visualization
Closed

Panav/feat/update mppi visualization#5975
Pana1v wants to merge 16 commits intoros-navigation:mainfrom
Pana1v:panav/feat/update-mppi-visualization

Conversation

@Pana1v
Copy link
Copy Markdown
Contributor

@Pana1v Pana1v commented Feb 22, 2026


Basic Info

Info Please fill out this column
Ticket(s) this addresses #5800
Primary OS tested on Ubuntu
Robotic platform tested on N/A
Does this PR contain AI generated software? No
Was this PR description generated by AI software? No

Description of contribution in a few bullet points

  • Built upon @tonynajjar's visualization PR, addressing feedback from @SteveMacenski
  • Renamed per-critic visualize_furthest_point parameter to debug_visualizations so each critic has a single toggle for all its debug visuals
  • Moved createTrajectoryMarkers and createFootprintMarkers from class methods to inline free functions in utils.hpp for easier unit testing
  • Vectorized cost normalization using Eigen (minCoeff/maxCoeff and array ops) instead of manual loops

Description of documentation updates required from your changes

  • Parameter rename: visualize_furthest_pointdebug_visualizations for PathAlignCritic, PathAngleCritic, PathFollowCritic

Description of how this change was tested

  • Performed linting validation using pre-commit run --all or colcon test

Future work that may be required in bullet points

  • Unit tests for the new free functions createTrajectoryMarkers and createFootprintMarkers in utils.hpp

@mergify
Copy link
Copy Markdown
Contributor

mergify bot commented Feb 22, 2026

This pull request is in conflict. Could you fix it @Pana1v?

@mergify
Copy link
Copy Markdown
Contributor

mergify bot commented Feb 22, 2026

@Pana1v, your PR has failed to build. Please check CI outputs and resolve issues.
You may need to rebase or pull in main due to API changes (or your contribution genuinely fails).

@Pana1v Pana1v force-pushed the panav/feat/update-mppi-visualization branch 3 times, most recently from 588558a to 0f40963 Compare February 22, 2026 18:04
…ions in utils.hpp for easier unit testing

- Moved createTrajectoryMarkers and createFootprintMarkers from TrajectoryVisualizer class to inline free functions in utils.hpp
- Renamed visualize_furthest_point to debug_visualizations in path critic plugins
- Vectorized cost normalization using Eigen operations

Signed-off-by: Pana <panav@users.noreply.github.com>
Signed-off-by: Panav Arpit Raaj <praajarpit@gmail.com>
@Pana1v Pana1v force-pushed the panav/feat/update-mppi-visualization branch from 0f40963 to f996cd4 Compare February 22, 2026 18:29
@mini-1235
Copy link
Copy Markdown
Collaborator

Based on the CI results, it looks like this isn't compiling. If it is not ready for review yet, please convert it to a draft and ping us again once you have fully tested it locally :)

std::string frame_id_;
nav2::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr
trajectories_publisher_;
nav2::Publisher<nav_msgs::msg::Path>::SharedPtr transformed_path_pub_;
Copy link
Copy Markdown
Collaborator

Choose a reason for hiding this comment

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

Note that this is removed from mppi, see migration guide here https://docs.nav2.org/migration/Kilted.html#centralize-path-handler-logic-in-controller-server

@mini-1235 mini-1235 mentioned this pull request Feb 23, 2026
8 tasks
@Pana1v Pana1v marked this pull request as draft February 24, 2026 03:28
Signed-off-by: Panav Arpit Raaj <praajarpit@gmail.com>
@Pana1v Pana1v force-pushed the panav/feat/update-mppi-visualization branch from 855dcda to 52a9346 Compare February 28, 2026 09:09
@tonynajjar
Copy link
Copy Markdown
Contributor

@Pana1v how's this going? I'm going to need this soon again so let me know when it's ready for someone to test!

@Pana1v
Copy link
Copy Markdown
Contributor Author

Pana1v commented Mar 4, 2026

@Pana1v how's this going? I'm going to need this soon again so let me know when it's ready for someone to test!

Just sat down to work on this by coincidence, I've addressed most of the comments by Steve, was just setting up a local env for testing this out, if you could test it that would be even better!

@Pana1v Pana1v marked this pull request as ready for review March 4, 2026 13:47
@tonynajjar
Copy link
Copy Markdown
Contributor

Yeah will give it a try

@tonynajjar
Copy link
Copy Markdown
Contributor

@tonynajjar
Copy link
Copy Markdown
Contributor

tonynajjar commented Mar 4, 2026

I'm considering replacing costs_sum with more telling and useful metrics, namely:

costs_std_dev — the standard deviation of each critic's cost distribution across trajectories. It measures how much a critic differentiates between trajectories. A high σ means the critic strongly prefers some trajectories over others; a low σ means it scores them roughly equally (i.e., it's not influencing the selection much).

influence_ratio — each critic's σ divided by the sum of all critics' σ values (σ_k / Σσ_j). It measures what fraction of the total trajectory discrimination each critic is responsible for. If one critic has an influence_ratio of 0.8, it's doing 80% of the "deciding" — a signal that its weight may be too dominant.

What do you think? Would you add any extra metrics?

I have my changes in a branch, would you mind if I commit directly on your branch? Another option is that I reopen #5643

@Pana1v
Copy link
Copy Markdown
Contributor Author

Pana1v commented Mar 5, 2026

I'm considering replacing costs_sum with more telling and useful metrics, namely:

costs_std_dev — the standard deviation of each critic's cost distribution across trajectories. It measures how much a critic differentiates between trajectories. A high σ means the critic strongly prefers some trajectories over others; a low σ means it scores them roughly equally (i.e., it's not influencing the selection much).

influence_ratio — each critic's σ divided by the sum of all critics' σ values (σ_k / Σσ_j). It measures what fraction of the total trajectory discrimination each critic is responsible for. If one critic has an influence_ratio of 0.8, it's doing 80% of the "deciding" — a signal that its weight may be too dominant.

What do you think? Would you add any extra metrics?

I have my changes in a branch, would you mind if I commit directly on your branch? Another option is that I reopen #5643

Definitely more informative to have influence ratio, I was thinking of publishing weights as well, but it would get complicated since a critic such as for obstacle may have multiple weight fields.

I've sent an invite to add you on my fork so that there's minimum friction in incorporating changes on your branch.

@Alessio-Parmeggiani
Copy link
Copy Markdown

I'm considering replacing costs_sum with more telling and useful metrics, namely:

costs_std_dev — the standard deviation of each critic's cost distribution across trajectories. It measures how much a critic differentiates between trajectories. A high σ means the critic strongly prefers some trajectories over others; a low σ means it scores them roughly equally (i.e., it's not influencing the selection much).

influence_ratio — each critic's σ divided by the sum of all critics' σ values (σ_k / Σσ_j). It measures what fraction of the total trajectory discrimination each critic is responsible for. If one critic has an influence_ratio of 0.8, it's doing 80% of the "deciding" — a signal that its weight may be too dominant.

What do you think? Would you add any extra metrics?

I have my changes in a branch, would you mind if I commit directly on your branch? Another option is that I reopen #5643

Hello, I just want to add my two cents since I am working with MPPI and will find useful to have new debug information.

In previous projects I found useful to publish the normalized cost of each critic.
When generating the final trajectory the costs are normalized by subtracting the first value of each cost.

auto costs_normalized = costs_ - costs_.minCoeff();
const float inv_temp = 1.0f / s.temperature;
auto softmaxes = (-inv_temp * costs_normalized).exp().eval();
softmaxes /= softmaxes.sum();

Publishing these vallues would allow to examine the actual values that are used to generate the optimal trajectory in that time step.

Another thing I would like to say is to keep costs_sum because it is useful to check for the range of values of each critic, so during weight tuning it is possible to inspect these values and change the weights to avoid having critics that span values that are order of magnitude different.

it is possible to add more fields to CriticStats.msg so we can have different kind of informations.

Signed-off-by: Panav Arpit Raaj <praajarpit@gmail.com>
@codecov
Copy link
Copy Markdown

codecov bot commented Mar 6, 2026

Codecov Report

❌ Patch coverage is 57.31225% with 108 lines in your changes missing coverage. Please review.

Files with missing lines Patch % Lines
nav2_mppi_controller/src/critics_visualizer.cpp 34.37% 42 Missing ⚠️
...oller/include/nav2_mppi_controller/tools/utils.hpp 50.87% 28 Missing ⚠️
nav2_mppi_controller/src/trajectory_visualizer.cpp 65.33% 26 Missing ⚠️
...r/include/nav2_mppi_controller/critic_function.hpp 60.00% 10 Missing ⚠️
...troller/include/nav2_mppi_controller/optimizer.hpp 80.00% 1 Missing ⚠️
...2_mppi_controller/src/critics/obstacles_critic.cpp 66.66% 1 Missing ⚠️
Files with missing lines Coverage Δ
...roller/include/nav2_mppi_controller/controller.hpp 100.00% <ø> (ø)
...er/include/nav2_mppi_controller/critic_manager.hpp 100.00% <ø> (ø)
.../nav2_mppi_controller/tools/critics_visualizer.hpp 100.00% <100.00%> (ø)
...v2_mppi_controller/tools/trajectory_visualizer.hpp 100.00% <ø> (ø)
nav2_mppi_controller/src/controller.cpp 100.00% <100.00%> (+12.24%) ⬆️
nav2_mppi_controller/src/critic_manager.cpp 100.00% <100.00%> (ø)
nav2_mppi_controller/src/critics/cost_critic.cpp 85.00% <100.00%> (+0.58%) ⬆️
..._mppi_controller/src/critics/path_align_critic.cpp 94.20% <100.00%> (+0.35%) ⬆️
..._mppi_controller/src/critics/path_angle_critic.cpp 87.87% <100.00%> (+0.37%) ⬆️
...mppi_controller/src/critics/path_follow_critic.cpp 93.10% <100.00%> (+0.51%) ⬆️
... and 7 more

... and 18 files with indirect coverage changes

🚀 New features to boost your workflow:
  • ❄️ Test Analytics: Detect flaky tests, report on failures, and find test suite problems.

Pana1v and others added 6 commits March 7, 2026 02:58
Signed-off-by: Panav Arpit Raaj <praajarpit@gmail.com>
Signed-off-by: Panav Arpit Raaj <praajarpit@gmail.com>
Signed-off-by: Tony Najjar <tony.najjar@dexory.com>
Signed-off-by: Tony Najjar <tony.najjar@dexory.com>
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

This PR updates Nav2 MPPI controller visualization and critic introspection capabilities, including new per-trajectory LINE_STRIP visualization, per-critic cost breakdown support, and improved critic influence statistics.

Changes:

  • Replace candidate trajectory visualization with cost-colored line markers and add optional per-critic cost visualizations.
  • Update critics statistics message to publish discriminating power (costs_std_dev) and normalized influence (influence_ratio) instead of summed costs.
  • Introduce/standardize a Visualization parameter namespace and add critic-level debug_visualizations toggles for additional debug publishers.

Reviewed changes

Copilot reviewed 25 out of 25 changed files in this pull request and generated 11 comments.

Show a summary per file
File Description
nav2_msgs/msg/CriticsStats.msg Changes critic stats fields to costs_std_dev and influence_ratio.
nav2_mppi_controller/test/utils_test.cpp Updates CriticData aggregate init to match new struct layout.
nav2_mppi_controller/test/trajectory_visualizer_tests.cpp Adds tests for transformed path publishing and updates visualization API usage.
nav2_mppi_controller/test/critics_tests.cpp Updates CriticData init and adds “debug visualizations enabled” coverage for path critics.
nav2_mppi_controller/test/critic_manager_test.cpp Adds test for per-critic cost collection behavior.
nav2_mppi_controller/src/trajectory_visualizer.cpp Implements new visualization toggles/publishers and cost-colored trajectory markers.
nav2_mppi_controller/src/critics/path_follow_critic.cpp Adds debug_visualizations publisher for target pose visualization.
nav2_mppi_controller/src/critics/path_angle_critic.cpp Adds debug_visualizations publisher for target pose visualization.
nav2_mppi_controller/src/critics/path_align_critic.cpp Adds debug_visualizations publisher for furthest-point pose visualization.
nav2_mppi_controller/src/critics/obstacles_critic.cpp Adds trajectory collision mask population for stats filtering.
nav2_mppi_controller/src/critics/cost_critic.cpp Adds trajectory collision mask population for stats filtering.
nav2_mppi_controller/src/critic_manager.cpp Adds per-critic cost diffs collection and new std-dev/influence stats computation.
nav2_mppi_controller/src/controller.cpp Routes all visualization publishing through TrajectoryVisualizer::visualize(...).
nav2_mppi_controller/include/nav2_mppi_controller/tools/utils.hpp Adds free functions for trajectory/footprint marker creation.
nav2_mppi_controller/include/nav2_mppi_controller/tools/trajectory_visualizer.hpp Expands visualizer API to accept costs and additional publish options.
nav2_mppi_controller/include/nav2_mppi_controller/optimizer.hpp Exposes costs and per-critic costs for visualization.
nav2_mppi_controller/include/nav2_mppi_controller/critics/path_follow_critic.hpp Adds publisher members for debug visualization.
nav2_mppi_controller/include/nav2_mppi_controller/critics/path_angle_critic.hpp Adds publisher members for debug visualization.
nav2_mppi_controller/include/nav2_mppi_controller/critics/path_align_critic.hpp Adds publisher members for debug visualization.
nav2_mppi_controller/include/nav2_mppi_controller/critic_manager.hpp Adds visualize_per_critic_costs_ flag.
nav2_mppi_controller/include/nav2_mppi_controller/critic_function.hpp Stores a node clock pointer for timestamping debug messages.
nav2_mppi_controller/include/nav2_mppi_controller/critic_data.hpp Adds individual_critics_cost and trajectory_collisions optionals.
nav2_mppi_controller/include/nav2_mppi_controller/controller.hpp Removes legacy visualization-related members/methods from controller interface.
nav2_mppi_controller/README.md Updates docs for new critic stats fields.
nav2_bringup/params/nav2_params.yaml Updates MPPI params to new Visualization namespace and flags.

You can also share your feedback on Copilot code review. Take the survey.

Signed-off-by: Tony Najjar <tony.najjar@dexory.com>
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 25 out of 25 changed files in this pull request and generated 4 comments.


You can also share your feedback on Copilot code review. Take the survey.

Comment on lines +222 to +230
// Visualize trajectories with total costs
if (publish_trajectories_with_total_cost_) {
add(candidate_trajectories, costs, {}, stamp);
}

// Visualize trajectories with individual critic costs
if (publish_trajectories_with_individual_cost_ && !critic_costs.empty()) {
add(candidate_trajectories, costs, critic_costs, stamp);
}
Copy link

Copilot AI Mar 9, 2026

Choose a reason for hiding this comment

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

In visualize(), when both publish_trajectories_with_total_cost_ and publish_trajectories_with_individual_cost_ are enabled, add() is called twice and the second call will also re-add the "Total Costs" markers (since add() unconditionally adds total costs when publish_trajectories_with_total_cost_ is true). This will duplicate total-cost markers in the published MarkerArray. Consider calling add() only once when individual costs are available (passing critic_costs), or add a flag/branch so total-cost markers are generated exactly once per cycle.

Copilot uses AI. Check for mistakes.
Copy link
Copy Markdown
Contributor Author

Choose a reason for hiding this comment

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

Addressed, combined both if statements, it is gated in the add function already.

Comment on lines +934 to +936
state.local_path_length = std::abs(state.pose.pose.position.x - goal.position.x);
*data.furthest_reached_path_point = 9;
critic.score(data);
Copy link

Copilot AI Mar 9, 2026

Choose a reason for hiding this comment

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

furthest_reached_path_point is initialized as std::nullopt in this test, but the code dereferences it (*data.furthest_reached_path_point = 9;), which is undefined behavior and will crash. Assign the optional directly (e.g., data.furthest_reached_path_point = 9;) before scoring.

Copilot uses AI. Check for mistakes.
Comment on lines +972 to +974
state.pose.pose.position.x = 0.0;
*data.furthest_reached_path_point = 21;
for (int i = 0; i < 22; ++i) {
Copy link

Copilot AI Mar 9, 2026

Choose a reason for hiding this comment

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

furthest_reached_path_point is initialized as std::nullopt in this test, but the code dereferences it (*data.furthest_reached_path_point = 21;), which is undefined behavior and will crash. Assign the optional directly (e.g., data.furthest_reached_path_point = 21;) before scoring.

Copilot uses AI. Check for mistakes.
Comment on lines +58 to +62
@@ -59,7 +59,7 @@ This process is then repeated a number of times and returns a converged solution
| retry_attempt_limit | int | Default 1. Number of attempts to find feasible trajectory on failure for soft-resets before reporting failure. |
| regenerate_noises | bool | Default false. Whether to regenerate noises each iteration or use single noise distribution computed on initialization and reset. Practically, this is found to work fine since the trajectories are being sampled stochastically from a normal distribution and reduces compute jittering at run-time due to thread wake-ups to resample normal distribution. |
| publish_optimal_trajectory | bool | Publishes the full optimal trajectory sequence each control iteration for downstream control systems, collision checkers, etc to have context beyond the next timestep. |
| publish_critics_stats | bool | Default false. Whether to publish statistics about each critic's performance. When enabled, publishes a `nav2_msgs::msg::CriticsStats` message containing critic names, whether they changed costs, and the sum of costs added by each critic. Useful for debugging and tuning critic behavior. |
| publish_critics_stats | bool | Default false. Whether to publish statistics about each critic's performance. When enabled, publishes a `nav2_msgs::msg::CriticsStats` message containing critic names, discriminating power (std dev), and influence ratios. Useful for debugging and tuning critic behavior. |
Copy link

Copilot AI Mar 9, 2026

Choose a reason for hiding this comment

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

This parameter table still documents visualize, publish_optimal_trajectory, and the TrajectoryVisualizer: namespace as controller-level configuration, but the implementation and bringup params now use the unified <controller>.Visualization.* namespace (e.g., publish_optimal_trajectory_msg, publish_transformed_path, etc.) and the controller no longer reads visualize / publish_optimal_trajectory. Please update this section to reflect the new parameter names and namespace so users don't configure flags that are silently ignored.

Copilot uses AI. Check for mistakes.
Copy link
Copy Markdown
Contributor Author

Choose a reason for hiding this comment

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

Updated Readme to reflect the new schema

…d remove unused parameters

Signed-off-by: Tony Najjar <tony.najjar@dexory.com>
…rver visualization settings

Signed-off-by: Tony Najjar <tony.najjar@dexory.com>
Signed-off-by: Tony Najjar <tony.najjar@dexory.com>
@SteveMacenski
Copy link
Copy Markdown
Member

@tonynajjar can you review and let me know if you approve now?

…e addition of candidate trajectories

Signed-off-by: Panav Arpit Raaj <praajarpit@gmail.com>
@Pana1v
Copy link
Copy Markdown
Contributor Author

Pana1v commented Mar 15, 2026

@tonynajjar I tested it on my PC, might just be my rig but it was a little slow, there was some latency in the visualizations can you try and confirm for once if it works smoothly on yours ?

…threshold

The test set goal distance to 0.15m but PathFollowCritic::score() early-returns
when local_path_length < threshold_to_consider (default 1.4m), so costs were
always zero.

Signed-off-by: Panav Arpit Raaj <praajarpit@gmail.com>
EXPECT_NEAR(costs(1), 19.845, 0.01);
}

TEST(CriticTests, PathFollowCriticDebugVisualization)
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

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

Here and below: how do these test visualizations? There's not a subscriber to any of it nor is it testing the new fields recorded -- only the main costs. .

Comment on lines +45 to +46
node->declare_parameter(
"my_name.Visualization.publish_trajectories_with_total_cost", rclcpp::ParameterValue(true));
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

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

Where are these results evaulated?

temperature: 0.3
gamma: 0.015
motion_model: "DiffDrive"
visualize: false
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

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

I think as I mentioned to @tonynajjar I don't want there to be a ton of these publish_XYZ debug parameters. I think there should be 1. Visualize / debug or not. You then publish all or nothign. Its just too much to break out individually and you can always just check if the publisher has any subscriptions to pass population/publication if no one is listening to that one.

As such, the namespace, each of the publish_ can be removed.

publish_optimal_path/publish_optimal_trajectory_msg (which ever existed before, it looks like its been renamed or something) is not a debug topic, that should be removed back to the global namespace

return std::min(upper_bound, std::max(input, lower_bound));
}

/**
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

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

These additions are visualization-specific and I think can live in the vissualization class

rclcpp::Logger logger_{rclcpp::get_logger("MPPIController")};
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
nav2::Publisher<nav2_msgs::msg::Trajectory>::SharedPtr opt_traj_pub_;
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

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

Add this back, this is not debug.

Comment on lines +154 to +156
tf2::Quaternion quat;
quat.setRPY(0.0, 0.0, yaw);
msg->pose.orientation = tf2::toMsg(quat);
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

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

nav2 utils has a function for this

* @brief Initialize a debug pose publisher for this critic
* @param topic Topic name suffix (e.g. "furthest_reached_path_point")
*/
void initDebugPosePublisher(const std::string & topic)
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

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

@tonynajjar what do you think? I don't love the idea of each critic having this internally, rather the responsibility of the manager / visualizer?

if (critics_data_.individual_critics_cost) {
return *critics_data_.individual_critics_cost;
}
static const std::vector<std::pair<std::string, Eigen::ArrayXf>> empty;
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

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

Why static?

data.trajectory_collisions = Eigen::Array<bool, Eigen::Dynamic, 1>(data.costs.rows());
data.trajectory_collisions->setConstant(false);
}

Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

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

@tonynajjar thoughts? I do not love the idea of exposing this into the critics. Is this something you really want? Architecturally it is bad design and will slow down the controller and prime for buggyness

@tonynajjar
Copy link
Copy Markdown
Contributor

tonynajjar commented Mar 19, 2026

Hey @Pana1v, after some reflection we believe my original implementation was a bit too intrusive so I started again from scratch with another approach and it is now merged: #6036

Thanks for your efforts pushing this forward though. If you would still like to contribute in this direction, the visualization of the furthest_reached_path_point from some critics, was not included in that PR and would love to see it! (I'm actually needing it right now 😅 )

@tonynajjar tonynajjar closed this Mar 19, 2026
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.

7 participants