Nav2 Navigation Stack - kilted  kilted
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 "rcl_interfaces/msg/parameter_descriptor.hpp"
23 #include "nav2_util/node_thread.hpp"
24 #include "rclcpp_lifecycle/lifecycle_node.hpp"
25 #include "rclcpp/rclcpp.hpp"
26 #include "bondcpp/bond.hpp"
27 #include "bond/msg/constants.hpp"
28 
29 namespace nav2_util
30 {
31 
32 using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
33 
38 class LifecycleNode : public rclcpp_lifecycle::LifecycleNode
39 {
40 public:
48  const std::string & node_name,
49  const std::string & ns = "",
50  const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
51  virtual ~LifecycleNode();
52 
53  typedef struct
54  {
55  double from_value;
56  double to_value;
57  double step;
59 
60  typedef struct
61  {
62  int from_value;
63  int to_value;
64  int step;
65  } integer_range;
66 
76  const std::string & name, const rclcpp::ParameterValue & default_value,
77  const std::string & description = "", const std::string & additional_constraints = "",
78  bool read_only = false)
79  {
80  auto descriptor = rcl_interfaces::msg::ParameterDescriptor();
81 
82  descriptor.name = name;
83  descriptor.description = description;
84  descriptor.additional_constraints = additional_constraints;
85  descriptor.read_only = read_only;
86 
87  declare_parameter(descriptor.name, default_value, descriptor);
88  }
89 
100  const std::string & name, const rclcpp::ParameterValue & default_value,
101  const floating_point_range fp_range,
102  const std::string & description = "", const std::string & additional_constraints = "",
103  bool read_only = false)
104  {
105  auto descriptor = rcl_interfaces::msg::ParameterDescriptor();
106 
107  descriptor.name = name;
108  descriptor.description = description;
109  descriptor.additional_constraints = additional_constraints;
110  descriptor.read_only = read_only;
111  descriptor.floating_point_range.resize(1);
112  descriptor.floating_point_range[0].from_value = fp_range.from_value;
113  descriptor.floating_point_range[0].to_value = fp_range.to_value;
114  descriptor.floating_point_range[0].step = fp_range.step;
115 
116  declare_parameter(descriptor.name, default_value, descriptor);
117  }
118 
129  const std::string & name, const rclcpp::ParameterValue & default_value,
130  const integer_range int_range,
131  const std::string & description = "", const std::string & additional_constraints = "",
132  bool read_only = false)
133  {
134  auto descriptor = rcl_interfaces::msg::ParameterDescriptor();
135 
136  descriptor.name = name;
137  descriptor.description = description;
138  descriptor.additional_constraints = additional_constraints;
139  descriptor.read_only = read_only;
140  descriptor.integer_range.resize(1);
141  descriptor.integer_range[0].from_value = int_range.from_value;
142  descriptor.integer_range[0].to_value = int_range.to_value;
143  descriptor.integer_range[0].step = int_range.step;
144 
145  declare_parameter(descriptor.name, default_value, descriptor);
146  }
147 
151  std::shared_ptr<nav2_util::LifecycleNode> shared_from_this()
152  {
153  return std::static_pointer_cast<nav2_util::LifecycleNode>(
154  rclcpp_lifecycle::LifecycleNode::shared_from_this());
155  }
156 
163  nav2_util::CallbackReturn on_error(const rclcpp_lifecycle::State & /*state*/)
164  {
165  RCLCPP_FATAL(
166  get_logger(),
167  "Lifecycle node %s does not have error state implemented", get_name());
168  return nav2_util::CallbackReturn::SUCCESS;
169  }
170 
174  void autostart();
175 
181  virtual void on_rcl_preshutdown();
182 
186  void createBond();
187 
191  void destroyBond();
192 
193 protected:
198 
205  std::unique_ptr<rclcpp::PreShutdownCallbackHandle> rcl_preshutdown_cb_handle_{nullptr};
206 
210  void runCleanups();
211 
212  // Connection to tell that server is still up
213  std::shared_ptr<bond::Bond> bond_{nullptr};
214  double bond_heartbeat_period;
215  rclcpp::TimerBase::SharedPtr autostart_timer_;
216 };
217 
218 } // namespace nav2_util
219 
220 #endif // NAV2_UTIL__LIFECYCLE_NODE_HPP_
A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters.
void autostart()
Automatically configure and active the node.
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.