Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
controller.hpp
1 // Copyright (c) 2024 Open Navigation LLC
2 // Copyright (c) 2024 Alberto J. Tudela Roldán
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License.
15 
16 #ifndef OPENNAV_DOCKING__CONTROLLER_HPP_
17 #define OPENNAV_DOCKING__CONTROLLER_HPP_
18 
19 #include <memory>
20 #include <string>
21 #include <vector>
22 
23 #include "geometry_msgs/msg/pose.hpp"
24 #include "geometry_msgs/msg/twist.hpp"
25 #include "nav2_costmap_2d/costmap_subscriber.hpp"
26 #include "nav2_costmap_2d/footprint_subscriber.hpp"
27 #include "nav2_costmap_2d/costmap_topic_collision_checker.hpp"
28 #include "nav2_graceful_controller/smooth_control_law.hpp"
29 #include "nav_msgs/msg/path.hpp"
30 #include "nav2_util/lifecycle_node.hpp"
31 
32 namespace opennav_docking
33 {
39 {
40 public:
49  Controller(
50  const rclcpp_lifecycle::LifecycleNode::SharedPtr & node, std::shared_ptr<tf2_ros::Buffer> tf,
51  std::string fixed_frame, std::string base_frame);
52 
56  ~Controller();
57 
67  const geometry_msgs::msg::Pose & pose, geometry_msgs::msg::Twist & cmd, bool is_docking,
68  bool backward = false);
69 
70 protected:
80  const geometry_msgs::msg::Pose & target_pose, bool is_docking, bool backward = false);
81 
87  rcl_interfaces::msg::SetParametersResult
88  dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
89 
99  const rclcpp_lifecycle::LifecycleNode::SharedPtr & node,
100  std::string costmap_topic, std::string footprint_topic, double transform_tolerance);
101 
102  // Dynamic parameters handler
103  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
104  std::mutex dynamic_params_lock_;
105 
106  rclcpp::Logger logger_{rclcpp::get_logger("Controller")};
107  rclcpp::Clock::SharedPtr clock_;
108 
109  // Smooth control law
110  std::unique_ptr<nav2_graceful_controller::SmoothControlLaw> control_law_;
111  double k_phi_, k_delta_, beta_, lambda_;
112  double slowdown_radius_, v_linear_min_, v_linear_max_, v_angular_max_;
113 
114  // The trajectory of the robot while dock / undock for visualization / debug purposes
115  rclcpp::Publisher<nav_msgs::msg::Path>::SharedPtr trajectory_pub_;
116 
117  // Used for collision checking
118  bool use_collision_detection_;
119  double projection_time_;
120  double simulation_time_step_;
121  double dock_collision_threshold_;
122  double transform_tolerance_;
123  std::shared_ptr<tf2_ros::Buffer> tf2_buffer_;
124  std::unique_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub_;
125  std::unique_ptr<nav2_costmap_2d::FootprintSubscriber> footprint_sub_;
126  std::shared_ptr<nav2_costmap_2d::CostmapTopicCollisionChecker> collision_checker_;
127  std::string fixed_frame_, base_frame_;
128 };
129 
130 } // namespace opennav_docking
131 
132 #endif // OPENNAV_DOCKING__CONTROLLER_HPP_
Default control law for approaching a dock target.
Definition: controller.hpp:39
bool isTrajectoryCollisionFree(const geometry_msgs::msg::Pose &target_pose, bool is_docking, bool backward=false)
Check if a trajectory is collision free.
Definition: controller.cpp:120
bool computeVelocityCommand(const geometry_msgs::msg::Pose &pose, geometry_msgs::msg::Twist &cmd, bool is_docking, bool backward=false)
Compute a velocity command using control law.
Definition: controller.cpp:111
~Controller()
A destructor for opennav_docking::Controller.
Definition: controller.cpp:102
void configureCollisionChecker(const rclcpp_lifecycle::LifecycleNode::SharedPtr &node, std::string costmap_topic, std::string footprint_topic, double transform_tolerance)
Configure the collision checker.
Definition: controller.cpp:193
Controller(const rclcpp_lifecycle::LifecycleNode::SharedPtr &node, std::shared_ptr< tf2_ros::Buffer > tf, std::string fixed_frame, std::string base_frame)
Create a controller instance. Configure ROS 2 parameters.
Definition: controller.cpp:28
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
Definition: controller.cpp:205