Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
graceful_controller.hpp
1 // Copyright (c) 2023 Alberto J. Tudela Roldán
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_GRACEFUL_CONTROLLER__GRACEFUL_CONTROLLER_HPP_
16 #define NAV2_GRACEFUL_CONTROLLER__GRACEFUL_CONTROLLER_HPP_
17 
18 #include <string>
19 #include <limits>
20 #include <vector>
21 #include <memory>
22 #include <algorithm>
23 #include <mutex>
24 
25 #include "nav2_core/controller.hpp"
26 #include "nav2_costmap_2d/footprint_collision_checker.hpp"
27 #include "rclcpp/rclcpp.hpp"
28 #include "pluginlib/class_loader.hpp"
29 #include "pluginlib/class_list_macros.hpp"
30 #include "nav2_graceful_controller/path_handler.hpp"
31 #include "nav2_graceful_controller/parameter_handler.hpp"
32 #include "nav2_graceful_controller/smooth_control_law.hpp"
33 #include "nav2_graceful_controller/utils.hpp"
34 
35 namespace nav2_graceful_controller
36 {
37 
43 {
44 public:
48  GracefulController() = default;
49 
53  ~GracefulController() override = default;
54 
62  void configure(
63  const nav2::LifecycleNode::WeakPtr & parent,
64  std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
65  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) override;
66 
70  void cleanup() override;
71 
75  void activate() override;
76 
80  void deactivate() override;
81 
89  geometry_msgs::msg::TwistStamped computeVelocityCommands(
90  const geometry_msgs::msg::PoseStamped & pose,
91  const geometry_msgs::msg::Twist & velocity,
92  nav2_core::GoalChecker * goal_checker) override;
93 
98  void setPlan(const nav_msgs::msg::Path & path) override;
99 
107  void setSpeedLimit(const double & speed_limit, const bool & percentage) override;
108 
109 protected:
121  bool simulateTrajectory(
122  const geometry_msgs::msg::PoseStamped & motion_target,
123  const geometry_msgs::msg::TransformStamped & costmap_transform,
124  nav_msgs::msg::Path & trajectory,
125  geometry_msgs::msg::TwistStamped & cmd_vel,
126  bool backward);
127 
134  geometry_msgs::msg::Twist rotateToTarget(double angle_to_target);
135 
143  bool inCollision(const double & x, const double & y, const double & theta);
144 
151  const std::vector<geometry_msgs::msg::PoseStamped> & poses,
152  std::vector<double> & distances);
153 
158  void validateOrientations(std::vector<geometry_msgs::msg::PoseStamped> & path);
159 
160  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
161  std::string plugin_name_;
162  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
163  std::unique_ptr<nav2_costmap_2d::FootprintCollisionChecker<nav2_costmap_2d::Costmap2D *>>
164  collision_checker_;
165  rclcpp::Logger logger_{rclcpp::get_logger("GracefulController")};
166 
167  Parameters * params_;
168  double goal_dist_tolerance_;
169  bool goal_reached_;
170 
171  // True from the time a new path arrives until we have completed an initial rotation
172  bool do_initial_rotation_;
173 
174  nav2::Publisher<nav_msgs::msg::Path>::SharedPtr transformed_plan_pub_;
175  nav2::Publisher<nav_msgs::msg::Path>::SharedPtr local_plan_pub_;
176  nav2::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr motion_target_pub_;
177  nav2::Publisher<visualization_msgs::msg::Marker>::SharedPtr slowdown_pub_;
178  std::unique_ptr<nav2_graceful_controller::PathHandler> path_handler_;
179  std::unique_ptr<nav2_graceful_controller::ParameterHandler> param_handler_;
180  std::unique_ptr<nav2_graceful_controller::SmoothControlLaw> control_law_;
181 };
182 
183 } // namespace nav2_graceful_controller
184 
185 #endif // NAV2_GRACEFUL_CONTROLLER__GRACEFUL_CONTROLLER_HPP_
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.
void activate() override
Activate controller state machine.
~GracefulController() override=default
Destructor for nav2_graceful_controller::GracefulController.
void setPlan(const nav_msgs::msg::Path &path) override
nav2_core setPlan - Sets the global plan.
void computeDistanceAlongPath(const std::vector< geometry_msgs::msg::PoseStamped > &poses, std::vector< double > &distances)
Compute the distance to each pose in a path.
void deactivate() override
Deactivate controller state machine.
bool simulateTrajectory(const geometry_msgs::msg::PoseStamped &motion_target, const geometry_msgs::msg::TransformStamped &costmap_transform, nav_msgs::msg::Path &trajectory, geometry_msgs::msg::TwistStamped &cmd_vel, bool backward)
Simulate trajectory calculating in every step the new velocity command based on a new curvature value...
GracefulController()=default
Constructor for nav2_graceful_controller::GracefulController.
void cleanup() override
Cleanup controller state machine.
geometry_msgs::msg::Twist rotateToTarget(double angle_to_target)
Rotate the robot to face the motion target with maximum angular velocity.
void setSpeedLimit(const double &speed_limit, const bool &percentage) override
Limits the maximum linear speed of the robot.
void configure(const nav2::LifecycleNode::WeakPtr &parent, std::string name, std::shared_ptr< tf2_ros::Buffer > tf, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros) override
Configure controller state machine.
geometry_msgs::msg::TwistStamped computeVelocityCommands(const geometry_msgs::msg::PoseStamped &pose, const geometry_msgs::msg::Twist &velocity, nav2_core::GoalChecker *goal_checker) override
Compute the best command given the current pose and velocity.
bool inCollision(const double &x, const double &y, const double &theta)
Checks if the robot is in collision.
void validateOrientations(std::vector< geometry_msgs::msg::PoseStamped > &path)
Control law requires proper orientations, not all planners provide them.