Nav2 Navigation Stack - rolling  main
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 #include "nav2_ros_common/lifecycle_node.hpp"
27 #include "nav2_core/controller.hpp"
28 #include "nav2_core/goal_checker.hpp"
29 
30 namespace nav2_mppi_controller
31 {
32 
33 using namespace mppi; // NOLINT
34 
40 {
41 public:
45  MPPIController() = default;
46 
54  void configure(
55  const nav2::LifecycleNode::WeakPtr & parent,
56  std::string name, const std::shared_ptr<tf2_ros::Buffer> tf,
57  const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) override;
58 
62  void cleanup() override;
63 
67  void activate() override;
68 
72  void deactivate() override;
73 
77  void reset() override;
78 
85  geometry_msgs::msg::TwistStamped computeVelocityCommands(
86  const geometry_msgs::msg::PoseStamped & robot_pose,
87  const geometry_msgs::msg::Twist & robot_speed,
88  nav2_core::GoalChecker * goal_checker) override;
89 
94  void setPlan(const nav_msgs::msg::Path & path) override;
95 
101  void setSpeedLimit(const double & speed_limit, const bool & percentage) override;
102 
103 protected:
110  void visualize(
111  nav_msgs::msg::Path transformed_plan,
112  const builtin_interfaces::msg::Time & cmd_stamp,
113  const Eigen::ArrayXXf & optimal_trajectory);
114 
115  std::string name_;
116  nav2::LifecycleNode::WeakPtr parent_;
117  rclcpp::Logger logger_{rclcpp::get_logger("MPPIController")};
118  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
119  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
120  nav2::Publisher<nav2_msgs::msg::Trajectory>::SharedPtr opt_traj_pub_;
121 
122  std::unique_ptr<ParametersHandler> parameters_handler_;
123  Optimizer optimizer_;
124  PathHandler path_handler_;
125  TrajectoryVisualizer trajectory_visualizer_;
126 
127  bool visualize_;
128  bool publish_optimal_trajectory_;
129 };
130 
131 } // namespace nav2_mppi_controller
132 
133 #endif // NAV2_MPPI_CONTROLLER__CONTROLLER_HPP_
Main algorithm optimizer of the MPPI Controller.
Definition: optimizer.hpp:56
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:60
Function-object for checking whether a goal has been reached.
MPPIController()=default
Constructor for mppi::MPPIController.