Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
controller.hpp
1 // Copyright (c) 2022 Samsung Research America, @artofnothingness Alexey Budyakov
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef NAV2_MPPI_CONTROLLER__CONTROLLER_HPP_
16 #define NAV2_MPPI_CONTROLLER__CONTROLLER_HPP_
17 
18 #include <string>
19 #include <memory>
20 
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"
26 
27 #include "nav2_core/controller.hpp"
28 #include "nav2_core/goal_checker.hpp"
29 #include "rclcpp/rclcpp.hpp"
30 
31 namespace nav2_mppi_controller
32 {
33 
34 using namespace mppi; // NOLINT
35 
41 {
42 public:
46  MPPIController() = default;
47 
55  void configure(
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;
59 
63  void cleanup() override;
64 
68  void activate() override;
69 
73  void deactivate() override;
74 
78  void reset() override;
79 
86  geometry_msgs::msg::TwistStamped computeVelocityCommands(
87  const geometry_msgs::msg::PoseStamped & robot_pose,
88  const geometry_msgs::msg::Twist & robot_speed,
89  nav2_core::GoalChecker * goal_checker) override;
90 
95  void setPlan(const nav_msgs::msg::Path & path) override;
96 
102  void setSpeedLimit(const double & speed_limit, const bool & percentage) override;
103 
104 protected:
109  void visualize(
110  nav_msgs::msg::Path transformed_plan,
111  const builtin_interfaces::msg::Time & cmd_stamp);
112 
113  std::string name_;
114  rclcpp_lifecycle::LifecycleNode::WeakPtr parent_;
115  rclcpp::Logger logger_{rclcpp::get_logger("MPPIController")};
116  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
117  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
118 
119  std::unique_ptr<ParametersHandler> parameters_handler_;
120  Optimizer optimizer_;
121  PathHandler path_handler_;
122  TrajectoryVisualizer trajectory_visualizer_;
123 
124  bool visualize_;
125 };
126 
127 } // namespace nav2_mppi_controller
128 
129 #endif // NAV2_MPPI_CONTROLLER__CONTROLLER_HPP_
Main algorithm optimizer of the MPPI Controller.
Definition: optimizer.hpp:58
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
Definition: controller.hpp:61
Function-object for checking whether a goal has been reached.
MPPIController()=default
Constructor for mppi::MPPIController.