-
Notifications
You must be signed in to change notification settings - Fork 1.6k
MPPI cost-based visualization #5643
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
base: main
Are you sure you want to change the base?
Changes from all commits
2d429c6
f0f3333
cecc6ea
5202339
88a4adc
8ab4228
d1092e7
081e54d
b9f522e
9c23e57
1890dd9
b400b90
a3611d4
41b4c35
0f57a9c
70e7162
a88f5dc
badadf1
303e0cb
aa608c0
bb1792c
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
| Original file line number | Diff line number | Diff line change |
|---|---|---|
|
|
@@ -138,12 +138,18 @@ controller_server: | |
| temperature: 0.3 | ||
| gamma: 0.015 | ||
| motion_model: "DiffDrive" | ||
| visualize: true | ||
| publish_optimal_trajectory: true | ||
| regenerate_noises: true | ||
| TrajectoryVisualizer: | ||
| Visualization: | ||
|
Member
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. What happened to
Contributor
Author
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
I replaced it with more granular configurations because some topics e.g. candidate_trajectories are much heavier than others and for my use case I'd like to have the optimal_path always published and rosbag-recorded, even in production, but not the candidate trajectories. Alternatively we could have the catch-all What strategy would you follow?
Since it now includes params not directly related to the candidate trajectories, e.g. publish_transformed_path, I thought I'd rename it to something more general but if it creates unnecessary migration effort for everyone, I can revert to |
||
| publish_critics_stats: false | ||
| publish_optimal_trajectory_msg: false | ||
| publish_transformed_path: false | ||
|
Member
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. @mini-1235 I think this should be removed with your refactor, yes?
Contributor
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. If you are talking about |
||
| publish_trajectories_with_total_cost: false | ||
| publish_trajectories_with_individual_cost: false | ||
| publish_optimal_footprints: false | ||
| publish_optimal_path: false | ||
|
Comment on lines
+146
to
+149
Member
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Please explain these. If they're general debugging and not for production, can't these just fall under a catch-all "debug_visualizations"
Contributor
Author
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. same answer as above |
||
| trajectory_step: 5 | ||
| time_step: 3 | ||
| footprint_downsample_factor: 3 | ||
|
Member
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Isn't this just
Contributor
Author
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I think you mean |
||
| TrajectoryValidator: | ||
| # The validator can be configured with additional parameters if needed. | ||
| plugin: "mppi::DefaultOptimalTrajectoryValidator" | ||
|
|
||
| Original file line number | Diff line number | Diff line change |
|---|---|---|
|
|
@@ -18,6 +18,8 @@ | |
| #include <Eigen/Dense> | ||
|
|
||
| #include <memory> | ||
| #include <string> | ||
| #include <utility> | ||
| #include <vector> | ||
|
|
||
| #include "geometry_msgs/msg/pose_stamped.hpp" | ||
|
|
@@ -44,6 +46,7 @@ struct CriticData | |
| const geometry_msgs::msg::Pose & goal; | ||
|
|
||
| Eigen::ArrayXf & costs; | ||
| std::optional<std::vector<std::pair<std::string, Eigen::ArrayXf>>> individual_critics_cost; | ||
|
Member
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Why optional? |
||
| float & model_dt; | ||
|
|
||
| bool fail_flag; | ||
|
|
||
| Original file line number | Diff line number | Diff line change |
|---|---|---|
|
|
@@ -20,6 +20,8 @@ | |
| #include <string> | ||
| #include <memory> | ||
| #include <tuple> | ||
| #include <utility> | ||
| #include <vector> | ||
|
|
||
| #include "rclcpp_lifecycle/lifecycle_node.hpp" | ||
|
|
||
|
|
@@ -118,6 +120,28 @@ class Optimizer | |
| */ | ||
| const models::ControlSequence & getOptimalControlSequence(); | ||
|
|
||
| /** | ||
| * @brief Get the costs for trajectories for visualization | ||
| * @return Costs array | ||
| */ | ||
| const Eigen::ArrayXf & getCosts() const | ||
| { | ||
| return costs_; | ||
| } | ||
|
|
||
| /** | ||
| * @brief Get the per-critic costs for trajectories for visualization | ||
| * @return Vector of (critic_name, costs) pairs | ||
| */ | ||
| const std::vector<std::pair<std::string, Eigen::ArrayXf>> & getCriticCosts() const | ||
| { | ||
| if (critics_data_.individual_critics_cost) { | ||
|
Member
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. When would this not be the case? |
||
| return *critics_data_.individual_critics_cost; | ||
| } | ||
| static const std::vector<std::pair<std::string, Eigen::ArrayXf>> empty; | ||
| return empty; | ||
| } | ||
|
|
||
| /** | ||
| * @brief Set the maximum speed based on the speed limits callback | ||
| * @param speed_limit Limit of the speed for use | ||
|
|
@@ -284,7 +308,7 @@ class Optimizer | |
|
|
||
| CriticData critics_data_ = { | ||
| state_, generated_trajectories_, path_, goal_, | ||
| costs_, settings_.model_dt, false, nullptr, nullptr, | ||
| costs_, std::nullopt, settings_.model_dt, false, nullptr, nullptr, | ||
| std::nullopt, std::nullopt}; /// Caution, keep references | ||
|
|
||
| rclcpp::Logger logger_{rclcpp::get_logger("MPPIController")}; | ||
|
|
||
| Original file line number | Diff line number | Diff line change |
|---|---|---|
|
|
@@ -19,14 +19,20 @@ | |
|
|
||
| #include <memory> | ||
| #include <string> | ||
| #include <utility> | ||
| #include <vector> | ||
|
|
||
| #include "nav_msgs/msg/path.hpp" | ||
| #include "nav2_msgs/msg/trajectory.hpp" | ||
| #include "nav2_ros_common/lifecycle_node.hpp" | ||
| #include "nav2_costmap_2d/costmap_2d_ros.hpp" | ||
| #include "nav2_costmap_2d/footprint.hpp" | ||
| #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" | ||
|
|
||
| #include "nav2_mppi_controller/tools/parameters_handler.hpp" | ||
| #include "nav2_mppi_controller/tools/utils.hpp" | ||
| #include "nav2_mppi_controller/models/trajectories.hpp" | ||
| #include "nav2_mppi_controller/models/control_sequence.hpp" | ||
|
|
||
| namespace mppi | ||
| { | ||
|
|
@@ -78,28 +84,85 @@ class TrajectoryVisualizer | |
| const builtin_interfaces::msg::Time & cmd_stamp); | ||
|
|
||
| /** | ||
| * @brief Add candidate trajectories to visualize | ||
| * @brief Add candidate trajectories with costs to visualize | ||
| * @param trajectories Candidate trajectories | ||
| * @param total_costs Total cost array for each trajectory | ||
| * @param individual_critics_cost Optional vector of (critic_name, cost_array) pairs for per-critic visualization | ||
| * @param cmd_stamp Timestamp for the markers | ||
| */ | ||
| void add(const models::Trajectories & trajectories, const std::string & marker_namespace); | ||
| void add( | ||
| const models::Trajectories & trajectories, | ||
| const Eigen::ArrayXf & total_costs, | ||
| const std::vector<std::pair<std::string, Eigen::ArrayXf>> & individual_critics_cost = {}, | ||
| const builtin_interfaces::msg::Time & cmd_stamp = builtin_interfaces::msg::Time()); | ||
|
Member
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. There should be no default value for time, that should be real at all times (har-de-har-har) |
||
|
|
||
| /** | ||
| * @brief Visualize all trajectory data in one call | ||
| * @param plan Transformed plan to visualize | ||
| * @param optimal_trajectory Optimal trajectory | ||
| * @param control_sequence Control sequence for optimal trajectory | ||
| * @param model_dt Model time step | ||
| * @param stamp Timestamp for the visualization | ||
| * @param costmap_ros Costmap ROS pointer | ||
| * @param candidate_trajectories Generated candidate trajectories | ||
| * @param costs Total costs for each trajectory | ||
| * @param critic_costs Per-critic costs for each trajectory | ||
| */ | ||
| void visualize( | ||
| nav_msgs::msg::Path plan, | ||
| const Eigen::ArrayXXf & optimal_trajectory, | ||
| const models::ControlSequence & control_sequence, | ||
| float model_dt, | ||
| const builtin_interfaces::msg::Time & stamp, | ||
| std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros, | ||
| const models::Trajectories & candidate_trajectories, | ||
| const Eigen::ArrayXf & costs, | ||
| const std::vector<std::pair<std::string, Eigen::ArrayXf>> & critic_costs); | ||
|
|
||
| /** | ||
| * @brief Visualize the plan | ||
| * @param plan Plan to visualize | ||
| * @brief Visualize without optimizer (for testing) | ||
| * @param plan Transformed plan to visualize | ||
| */ | ||
| void visualize(const nav_msgs::msg::Path & plan); | ||
| void visualize(nav_msgs::msg::Path plan); | ||
|
|
||
| /** | ||
| * @brief Reset object | ||
| */ | ||
| void reset(); | ||
|
|
||
| protected: | ||
| /** | ||
| * @brief Create trajectory markers with cost-based coloring | ||
| * @param trajectories Set of trajectories to visualize | ||
| * @param costs Cost array for each trajectory | ||
| * @param ns Namespace for the markers | ||
| * @param cmd_stamp Timestamp for the markers | ||
| */ | ||
| void createTrajectoryMarkers( | ||
|
Member
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Can't these be free utils functions like the others before? I don't think these require class members and make them more easily unit testable |
||
| const models::Trajectories & trajectories, | ||
| const Eigen::ArrayXf & costs, | ||
| const std::string & ns, | ||
| const builtin_interfaces::msg::Time & cmd_stamp); | ||
|
|
||
| /** | ||
| * @brief Create footprint markers from trajectory | ||
| * @param trajectory Optimal trajectory | ||
| * @param header Message header | ||
| * @param costmap_ros Costmap ROS pointer for footprint and frame information | ||
| * @return MarkerArray containing footprint polygons | ||
| */ | ||
| visualization_msgs::msg::MarkerArray createFootprintMarkers( | ||
| const Eigen::ArrayXXf & trajectory, | ||
| const std_msgs::msg::Header & header, | ||
| std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros); | ||
|
|
||
| std::string frame_id_; | ||
| nav2::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr | ||
| trajectories_publisher_; | ||
| nav2::Publisher<nav_msgs::msg::Path>::SharedPtr transformed_path_pub_; | ||
| nav2::Publisher<nav_msgs::msg::Path>::SharedPtr optimal_path_pub_; | ||
| nav2::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr optimal_footprints_pub_; | ||
| nav2::Publisher<nav2_msgs::msg::Trajectory>::SharedPtr optimal_trajectory_msg_pub_; | ||
|
|
||
| std::unique_ptr<nav_msgs::msg::Path> optimal_path_; | ||
| std::unique_ptr<visualization_msgs::msg::MarkerArray> points_; | ||
|
|
@@ -109,6 +172,13 @@ class TrajectoryVisualizer | |
|
|
||
| size_t trajectory_step_{0}; | ||
| size_t time_step_{0}; | ||
| bool publish_trajectories_with_total_cost_{false}; | ||
| bool publish_trajectories_with_individual_cost_{false}; | ||
| bool publish_optimal_footprints_{false}; | ||
| bool publish_optimal_trajectory_msg_{false}; | ||
| bool publish_transformed_path_{false}; | ||
| bool publish_optimal_path_{false}; | ||
| int footprint_downsample_factor_{3}; | ||
|
|
||
| rclcpp::Logger logger_{rclcpp::get_logger("MPPIController")}; | ||
| }; | ||
|
|
||
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
This is not for visualization, I think this should remain outside of the visualization namespace. THis is for practical use for applications that do not want a cmd_vel but need a full trajectory to work with (which exist)