15 #ifndef NAV2_MPPI_CONTROLLER__CONTROLLER_HPP_
16 #define NAV2_MPPI_CONTROLLER__CONTROLLER_HPP_
21 #include "nav2_mppi_controller/tools/path_handler.hpp"
22 #include "nav2_mppi_controller/optimizer.hpp"
23 #include "nav2_mppi_controller/tools/trajectory_visualizer.hpp"
24 #include "nav2_mppi_controller/models/constraints.hpp"
25 #include "nav2_mppi_controller/tools/utils.hpp"
27 #include "nav2_core/controller.hpp"
28 #include "nav2_core/goal_checker.hpp"
29 #include "rclcpp/rclcpp.hpp"
31 namespace nav2_mppi_controller
56 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
57 std::string name,
const std::shared_ptr<tf2_ros::Buffer> tf,
58 const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
override;
63 void cleanup()
override;
68 void activate()
override;
73 void deactivate()
override;
86 geometry_msgs::msg::TwistStamped computeVelocityCommands(
87 const geometry_msgs::msg::PoseStamped & robot_pose,
88 const geometry_msgs::msg::Twist & robot_speed,
95 void setPlan(
const nav_msgs::msg::Path & path)
override;
102 void setSpeedLimit(
const double & speed_limit,
const bool & percentage)
override;
109 void visualize(nav_msgs::msg::Path transformed_plan);
112 rclcpp_lifecycle::LifecycleNode::WeakPtr parent_;
113 rclcpp::Clock::SharedPtr clock_;
114 rclcpp::Logger logger_{rclcpp::get_logger(
"MPPIController")};
115 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
116 std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
118 std::unique_ptr<ParametersHandler> parameters_handler_;
125 double reset_period_;
127 rclcpp::Time last_time_called_;
Main algorithm optimizer of the MPPI Controller.
Manager of incoming reference paths for transformation and processing.
Visualizes trajectories for debugging.
controller interface that acts as a virtual base class for all controller plugins
Function-object for checking whether a goal has been reached.
MPPIController()=default
Constructor for mppi::MPPIController.