Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
lifecycle_node.hpp
1 // Copyright (c) 2019 Intel Corporation
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_UTIL__LIFECYCLE_NODE_HPP_
16 #define NAV2_UTIL__LIFECYCLE_NODE_HPP_
17 
18 #include <memory>
19 #include <string>
20 #include <thread>
21 
22 #include "nav2_util/node_thread.hpp"
23 #include "rclcpp_lifecycle/lifecycle_node.hpp"
24 #include "rclcpp/rclcpp.hpp"
25 #include "bondcpp/bond.hpp"
26 #include "bond/msg/constants.hpp"
27 
28 namespace nav2_util
29 {
30 
31 using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
32 
37 class LifecycleNode : public rclcpp_lifecycle::LifecycleNode
38 {
39 public:
47  const std::string & node_name,
48  const std::string & ns = "",
49  const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
50  virtual ~LifecycleNode();
51 
52  typedef struct
53  {
54  double from_value;
55  double to_value;
56  double step;
58 
59  typedef struct
60  {
61  int from_value;
62  int to_value;
63  int step;
64  } integer_range;
65 
75  const std::string & name, const rclcpp::ParameterValue & default_value,
76  const std::string & description = "", const std::string & additional_constraints = "",
77  bool read_only = false)
78  {
79  auto descriptor = rcl_interfaces::msg::ParameterDescriptor();
80 
81  descriptor.name = name;
82  descriptor.description = description;
83  descriptor.additional_constraints = additional_constraints;
84  descriptor.read_only = read_only;
85 
86  declare_parameter(descriptor.name, default_value, descriptor);
87  }
88 
99  const std::string & name, const rclcpp::ParameterValue & default_value,
100  const floating_point_range fp_range,
101  const std::string & description = "", const std::string & additional_constraints = "",
102  bool read_only = false)
103  {
104  auto descriptor = rcl_interfaces::msg::ParameterDescriptor();
105 
106  descriptor.name = name;
107  descriptor.description = description;
108  descriptor.additional_constraints = additional_constraints;
109  descriptor.read_only = read_only;
110  descriptor.floating_point_range.resize(1);
111  descriptor.floating_point_range[0].from_value = fp_range.from_value;
112  descriptor.floating_point_range[0].to_value = fp_range.to_value;
113  descriptor.floating_point_range[0].step = fp_range.step;
114 
115  declare_parameter(descriptor.name, default_value, descriptor);
116  }
117 
128  const std::string & name, const rclcpp::ParameterValue & default_value,
129  const integer_range int_range,
130  const std::string & description = "", const std::string & additional_constraints = "",
131  bool read_only = false)
132  {
133  auto descriptor = rcl_interfaces::msg::ParameterDescriptor();
134 
135  descriptor.name = name;
136  descriptor.description = description;
137  descriptor.additional_constraints = additional_constraints;
138  descriptor.read_only = read_only;
139  descriptor.integer_range.resize(1);
140  descriptor.integer_range[0].from_value = int_range.from_value;
141  descriptor.integer_range[0].to_value = int_range.to_value;
142  descriptor.integer_range[0].step = int_range.step;
143 
144  declare_parameter(descriptor.name, default_value, descriptor);
145  }
146 
150  std::shared_ptr<nav2_util::LifecycleNode> shared_from_this()
151  {
152  return std::static_pointer_cast<nav2_util::LifecycleNode>(
153  rclcpp_lifecycle::LifecycleNode::shared_from_this());
154  }
155 
162  nav2_util::CallbackReturn on_error(const rclcpp_lifecycle::State & /*state*/)
163  {
164  RCLCPP_FATAL(
165  get_logger(),
166  "Lifecycle node %s does not have error state implemented", get_name());
167  return nav2_util::CallbackReturn::SUCCESS;
168  }
169 
175  virtual void on_rcl_preshutdown();
176 
180  void createBond();
181 
185  void destroyBond();
186 
187 protected:
192 
199  std::unique_ptr<rclcpp::PreShutdownCallbackHandle> rcl_preshutdown_cb_handle_{nullptr};
200 
204  void runCleanups();
205 
206  // Connection to tell that server is still up
207  std::unique_ptr<bond::Bond> bond_{nullptr};
208 };
209 
210 } // namespace nav2_util
211 
212 #endif // NAV2_UTIL__LIFECYCLE_NODE_HPP_
A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters.
void add_parameter(const std::string &name, const rclcpp::ParameterValue &default_value, const floating_point_range fp_range, const std::string &description="", const std::string &additional_constraints="", bool read_only=false)
Declare a parameter that has a floating point range constraint.
void add_parameter(const std::string &name, const rclcpp::ParameterValue &default_value, const std::string &description="", const std::string &additional_constraints="", bool read_only=false)
Declare a parameter that has no integer or floating point range constraints.
void add_parameter(const std::string &name, const rclcpp::ParameterValue &default_value, const integer_range int_range, const std::string &description="", const std::string &additional_constraints="", bool read_only=false)
Declare a parameter that has an integer range constraint.
LifecycleNode(const std::string &node_name, const std::string &ns="", const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
A lifecycle node constructor.
void printLifecycleNodeNotification()
Print notifications for lifecycle node.
nav2_util::CallbackReturn on_error(const rclcpp_lifecycle::State &)
Abstracted on_error state transition callback, since unimplemented as of 2020 in the managed ROS2 nod...
std::shared_ptr< nav2_util::LifecycleNode > shared_from_this()
Get a shared pointer of this.
virtual void on_rcl_preshutdown()
Perform preshutdown activities before our Context is shutdown. Note that this is related to our Conte...
void createBond()
Create bond connection to lifecycle manager.
void destroyBond()
Destroy bond connection to lifecycle manager.