15 #ifndef NAV2_MPPI_CONTROLLER__OPTIMIZER_HPP_
16 #define NAV2_MPPI_CONTROLLER__OPTIMIZER_HPP_
21 #include <xtensor/xtensor.hpp>
22 #include <xtensor/xview.hpp>
24 #include "rclcpp_lifecycle/lifecycle_node.hpp"
26 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
27 #include "nav2_core/goal_checker.hpp"
29 #include "geometry_msgs/msg/twist.hpp"
30 #include "geometry_msgs/msg/pose_stamped.hpp"
31 #include "geometry_msgs/msg/twist_stamped.hpp"
32 #include "nav_msgs/msg/path.hpp"
34 #include "nav2_mppi_controller/models/optimizer_settings.hpp"
35 #include "nav2_mppi_controller/motion_models.hpp"
36 #include "nav2_mppi_controller/critic_manager.hpp"
37 #include "nav2_mppi_controller/models/state.hpp"
38 #include "nav2_mppi_controller/models/trajectories.hpp"
39 #include "nav2_mppi_controller/models/path.hpp"
40 #include "nav2_mppi_controller/tools/noise_generator.hpp"
41 #include "nav2_mppi_controller/tools/parameters_handler.hpp"
42 #include "nav2_mppi_controller/tools/utils.hpp"
73 rclcpp_lifecycle::LifecycleNode::WeakPtr parent,
const std::string & name,
74 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros,
91 const geometry_msgs::msg::PoseStamped & robot_pose,
92 const geometry_msgs::msg::Twist & robot_speed,
const nav_msgs::msg::Path & plan,
133 const geometry_msgs::msg::PoseStamped & robot_pose,
134 const geometry_msgs::msg::Twist & robot_speed,
135 const nav_msgs::msg::Path & plan,
200 xt::xtensor<float, 2> & trajectories,
201 const xt::xtensor<float, 2> & state)
const;
214 geometry_msgs::msg::TwistStamped
227 void setOffset(
double controller_frequency);
236 rclcpp_lifecycle::LifecycleNode::WeakPtr parent_;
237 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
241 std::shared_ptr<MotionModel> motion_model_;
251 std::array<mppi::models::Control, 4> control_history_;
254 geometry_msgs::msg::Pose goal_;
255 xt::xtensor<float, 1> costs_;
258 state_, generated_trajectories_, path_, goal_,
259 costs_, settings_.model_dt,
false,
nullptr,
nullptr,
260 std::nullopt, std::nullopt};
262 rclcpp::Logger
logger_{rclcpp::get_logger(
"MPPIController")};
Manager of objective function plugins for scoring trajectories.
Generates noise trajectories from optimal trajectory.
Main algorithm optimizer of the MPPI Controller.
geometry_msgs::msg::TwistStamped evalControl(const geometry_msgs::msg::PoseStamped &robot_pose, const geometry_msgs::msg::Twist &robot_speed, const nav_msgs::msg::Path &plan, const geometry_msgs::msg::Pose &goal, nav2_core::GoalChecker *goal_checker)
Compute control using MPPI algorithm.
void updateStateVelocities(models::State &state) const
Update velocities in state.
void setMotionModel(const std::string &model)
Set the motion model of the vehicle platform.
void setOffset(double controller_frequency)
Using control frequence and time step size, determine if trajectory offset should be used to populate...
rclcpp::Logger logger_
Caution, keep references.
void prepare(const geometry_msgs::msg::PoseStamped &robot_pose, const geometry_msgs::msg::Twist &robot_speed, const nav_msgs::msg::Path &plan, const geometry_msgs::msg::Pose &goal, nav2_core::GoalChecker *goal_checker)
Prepare state information on new request for trajectory rollouts.
void integrateStateVelocities(models::Trajectories &trajectories, const models::State &state) const
Rollout velocities in state to poses.
~Optimizer()
Destructor for mppi::Optimizer.
void updateControlSequence()
Update control sequence with state controls weighted by costs using softmax function.
void generateNoisedTrajectories()
updates generated trajectories with noised trajectories from the last cycle's optimal control
bool fallback(bool fail)
Perform fallback behavior to try to recover from a set of trajectories in collision.
bool isHolonomic() const
Whether the motion model is holonomic.
models::Trajectories & getGeneratedTrajectories()
Get the trajectories generated in a cycle for visualization.
void updateInitialStateVelocities(models::State &state) const
Update initial velocity in state.
xt::xtensor< float, 2 > getOptimizedTrajectory()
Get the optimal trajectory for a cycle for visualization.
void shutdown()
Shutdown for optimizer at process end.
void optimize()
Main function to generate, score, and return trajectories.
void reset()
Reset the optimization problem to initial conditions.
Optimizer()=default
Constructor for mppi::Optimizer.
void setSpeedLimit(double speed_limit, bool percentage)
Set the maximum speed based on the speed limits callback.
void shiftControlSequence()
Shift the optimal control sequence after processing for next iterations initial conditions after exec...
void applyControlSequenceConstraints()
Apply hard vehicle constraints on control sequence.
void getParams()
Obtain the main controller's parameters.
void propagateStateVelocitiesFromInitials(models::State &state) const
predict velocities in state using model for time horizon equal to timesteps
void initialize(rclcpp_lifecycle::LifecycleNode::WeakPtr parent, const std::string &name, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros, ParametersHandler *dynamic_parameters_handler)
Initializes optimizer on startup.
geometry_msgs::msg::TwistStamped getControlFromSequenceAsTwist(const builtin_interfaces::msg::Time &stamp)
Convert control sequence to a twist commant.
Handles getting parameters and dynamic parmaeter changes.
Function-object for checking whether a goal has been reached.
A 2D costmap provides a mapping between points in the world and their associated "costs".
Data to pass to critics for scoring, including state, trajectories, pruned path, global goal,...
A control sequence over time (e.g. trajectory)
Settings for the optimizer to use.
Path represented as a tensor.
State information: velocities, controls, poses, speed.