Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
parameter_handler.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__PARAMETER_HANDLER_HPP_
16 #define NAV2_GRACEFUL_CONTROLLER__PARAMETER_HANDLER_HPP_
17 
18 #include <string>
19 #include <vector>
20 #include <memory>
21 #include <algorithm>
22 #include <mutex>
23 
24 #include "nav2_util/odometry_utils.hpp"
25 #include "nav2_util/geometry_utils.hpp"
26 #include "nav2_ros_common/lifecycle_node.hpp"
27 #include "nav2_ros_common/node_utils.hpp"
28 
29 namespace nav2_graceful_controller
30 {
31 
32 struct Parameters
33 {
34  double transform_tolerance;
35  double min_lookahead;
36  double max_lookahead;
37  double max_robot_pose_search_dist;
38  double k_phi;
39  double k_delta;
40  double beta;
41  double lambda;
42  double v_linear_min;
43  double v_linear_max;
44  double v_linear_max_initial;
45  double v_angular_max;
46  double v_angular_max_initial;
47  double v_angular_min_in_place;
48  double slowdown_radius;
49  bool initial_rotation;
50  double initial_rotation_tolerance;
51  bool prefer_final_rotation;
52  double rotation_scaling_factor;
53  bool allow_backward;
54  double in_place_collision_resolution;
55  bool use_collision_detection;
56 };
57 
63 {
64 public:
69  nav2::LifecycleNode::SharedPtr node,
70  std::string & plugin_name,
71  rclcpp::Logger & logger, const double costmap_size_x);
72 
77 
78  std::mutex & getMutex() {return mutex_;}
79 
80  Parameters * getParams() {return &params_;}
81 
82 protected:
83  nav2::LifecycleNode::WeakPtr node_;
84 
89  rcl_interfaces::msg::SetParametersResult
90  dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
91 
92  // Dynamic parameters handler
93  std::mutex mutex_;
94  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
95  Parameters params_;
96  std::string plugin_name_;
97  rclcpp::Logger logger_ {rclcpp::get_logger("GracefulMotionController")};
98 };
99 
100 } // namespace nav2_graceful_controller
101 
102 #endif // NAV2_GRACEFUL_CONTROLLER__PARAMETER_HANDLER_HPP_
Handles parameters and dynamic parameters for GracefulMotionController.
~ParameterHandler()
Destructor for nav2_graceful_controller::ParameterHandler.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
ParameterHandler(nav2::LifecycleNode::SharedPtr node, std::string &plugin_name, rclcpp::Logger &logger, const double costmap_size_x)
Constructor for nav2_graceful_controller::ParameterHandler.