Nav2 Navigation Stack - humble  humble
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 "rclcpp/rclcpp.hpp"
25 #include "rclcpp_lifecycle/lifecycle_node.hpp"
26 #include "nav2_util/odometry_utils.hpp"
27 #include "nav2_util/geometry_utils.hpp"
28 #include "nav2_util/node_utils.hpp"
29 
30 namespace nav2_graceful_controller
31 {
32 
33 struct Parameters
34 {
35  double transform_tolerance;
36  double motion_target_dist;
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 slowdown_radius;
48  bool initial_rotation;
49  double initial_rotation_min_angle;
50  bool final_rotation;
51  double rotation_scaling_factor;
52  bool allow_backward;
53 };
54 
60 {
61 public:
66  rclcpp_lifecycle::LifecycleNode::SharedPtr node,
67  std::string & plugin_name,
68  rclcpp::Logger & logger, const double costmap_size_x);
69 
73  ~ParameterHandler() = default;
74 
75  std::mutex & getMutex() {return mutex_;}
76 
77  Parameters * getParams() {return &params_;}
78 
79 protected:
84  rcl_interfaces::msg::SetParametersResult
85  dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
86 
87  // Dynamic parameters handler
88  std::mutex mutex_;
89  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
90  Parameters params_;
91  std::string plugin_name_;
92  rclcpp::Logger logger_ {rclcpp::get_logger("GracefulMotionController")};
93 };
94 
95 } // namespace nav2_graceful_controller
96 
97 #endif // NAV2_GRACEFUL_CONTROLLER__PARAMETER_HANDLER_HPP_
Handles parameters and dynamic parameters for GracefulMotionController.
~ParameterHandler()=default
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(rclcpp_lifecycle::LifecycleNode::SharedPtr node, std::string &plugin_name, rclcpp::Logger &logger, const double costmap_size_x)
Constructor for nav2_graceful_controller::ParameterHandler.