|
Nav2 Navigation Stack - rolling
main
ROS 2 Navigation Stack
|
Abstract base class for validating optimal trajectories from MPPI optimization. More...
#include <nav2_mppi_controller/include/nav2_mppi_controller/optimal_trajectory_validator.hpp>

Public Types | |
| using | Ptr = std::shared_ptr< OptimalTrajectoryValidator > |
Public Member Functions | |
| OptimalTrajectoryValidator ()=default | |
| Constructor for mppi::OptimalTrajectoryValidator. | |
| virtual | ~OptimalTrajectoryValidator ()=default |
| Destructor for mppi::OptimalTrajectoryValidator. | |
| virtual void | initialize (const nav2::LifecycleNode::WeakPtr &parent, const std::string &name, const std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap, ParametersHandler *param_handler, const std::shared_ptr< tf2_ros::Buffer > tf_buffer, const models::OptimizerSettings &settings) |
| Initialize the trajectory validator. More... | |
| virtual ValidationResult | validateTrajectory (const Eigen::ArrayXXf &optimal_trajectory, const models::ControlSequence &, const geometry_msgs::msg::PoseStamped &, const geometry_msgs::msg::Twist &, const nav_msgs::msg::Path &, const geometry_msgs::msg::Pose &) |
| Validate the optimal trajectory from MPPI optimization Could be used to check for collisions, progress towards goal, distance from path, min distance from obstacles, dynamic feasibility, etc. More... | |
Protected Attributes | |
| nav2::LifecycleNode::WeakPtr | node_ |
| std::string | name_ |
| std::shared_ptr< nav2_costmap_2d::Costmap2DROS > | costmap_ros_ |
| ParametersHandler * | param_handler_ |
| std::shared_ptr< tf2_ros::Buffer > | tf_buffer_ |
| float | collision_lookahead_time_ {1.0f} |
| unsigned int | traj_samples_to_evaluate_ {0u} |
| bool | consider_footprint_ {false} |
| std::unique_ptr< nav2_costmap_2d::FootprintCollisionChecker< nav2_costmap_2d::Costmap2D * > > | collision_checker_ |
Abstract base class for validating optimal trajectories from MPPI optimization.
Definition at line 47 of file optimal_trajectory_validator.hpp.
|
inlinevirtual |
Initialize the trajectory validator.
| node | Weak pointer to the lifecycle node |
| name | Name of the validator plugin |
| costmap | Shared pointer to the costmap ROS wrapper |
| param_handler | Pointer to the parameters handler |
| tf_buffer | Shared pointer to the TF buffer |
| settings | Settings for the MPPI optimizer |
Definition at line 71 of file optimal_trajectory_validator.hpp.
References mppi::ParametersHandler::getParamGetter().

|
inlinevirtual |
Validate the optimal trajectory from MPPI optimization Could be used to check for collisions, progress towards goal, distance from path, min distance from obstacles, dynamic feasibility, etc.
| optimal_trajectory | The optimal trajectory to validate |
| control_sequence | The control sequence to validate |
| robot_pose | The current pose of the robot |
| robot_speed | The current speed of the robot |
| plan | The planned path for the robot |
| goal | The goal pose for the robot |
Definition at line 117 of file optimal_trajectory_validator.hpp.