Nav2 Navigation Stack - humble  humble
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 rclcpp_lifecycle::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:
116  geometry_msgs::msg::PoseStamped getMotionTarget(
117  const double & motion_target_dist,
118  const nav_msgs::msg::Path & path);
119 
131  bool simulateTrajectory(
132  const geometry_msgs::msg::PoseStamped & robot_pose,
133  const geometry_msgs::msg::PoseStamped & motion_target,
134  const geometry_msgs::msg::TransformStamped & costmap_transform,
135  nav_msgs::msg::Path & trajectory,
136  const bool & backward);
137 
144  geometry_msgs::msg::Twist rotateToTarget(
145  const double & angle_to_target);
146 
154  bool inCollision(const double & x, const double & y, const double & theta);
155 
156  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
157  std::string plugin_name_;
158  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
159  std::unique_ptr<nav2_costmap_2d::FootprintCollisionChecker<nav2_costmap_2d::Costmap2D *>>
160  collision_checker_;
161  rclcpp::Logger logger_{rclcpp::get_logger("GracefulController")};
162 
163  Parameters * params_;
164  double goal_dist_tolerance_;
165  bool goal_reached_;
166 
167  std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>> transformed_plan_pub_;
168  std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>> local_plan_pub_;
169  std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PointStamped>>
170  motion_target_pub_;
171  std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<visualization_msgs::msg::Marker>>
172  slowdown_pub_;
173  std::unique_ptr<nav2_graceful_controller::PathHandler> path_handler_;
174  std::unique_ptr<nav2_graceful_controller::ParameterHandler> param_handler_;
175  std::unique_ptr<nav2_graceful_controller::SmoothControlLaw> control_law_;
176 };
177 
178 } // namespace nav2_graceful_controller
179 
180 #endif // NAV2_GRACEFUL_CONTROLLER__GRACEFUL_CONTROLLER_HPP_
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.
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.
bool simulateTrajectory(const geometry_msgs::msg::PoseStamped &robot_pose, const geometry_msgs::msg::PoseStamped &motion_target, const geometry_msgs::msg::TransformStamped &costmap_transform, nav_msgs::msg::Path &trajectory, const bool &backward)
Simulate trajectory calculating in every step the new velocity command based on a new curvature value...
void deactivate() override
Deactivate controller state machine.
geometry_msgs::msg::PoseStamped getMotionTarget(const double &motion_target_dist, const nav_msgs::msg::Path &path)
Get motion target point.
void configure(const rclcpp_lifecycle::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.
GracefulController()=default
Constructor for nav2_graceful_controller::GracefulController.
geometry_msgs::msg::Twist rotateToTarget(const double &angle_to_target)
Rotate the robot to face the motion target with maximum angular velocity.
void cleanup() override
Cleanup controller state machine.
void setSpeedLimit(const double &speed_limit, const bool &percentage) override
Limits the maximum linear speed of the robot.
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.