ROS 2 rclcpp + rcl - humble  humble
ROS 2 C++ Client Library with ROS Client Library
node_base.cpp
1 // Copyright 2016 Open Source Robotics Foundation, Inc.
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 #include <string>
16 #include <limits>
17 #include <memory>
18 #include <vector>
19 
20 #include "rclcpp/node_interfaces/node_base.hpp"
21 
22 #include "rcl/arguments.h"
23 #include "rclcpp/exceptions.hpp"
24 #include "rcutils/logging_macros.h"
25 #include "rmw/validate_namespace.h"
26 #include "rmw/validate_node_name.h"
27 
28 #include "../logging_mutex.hpp"
29 
30 using rclcpp::exceptions::throw_from_rcl_error;
31 
33 
34 NodeBase::NodeBase(
35  const std::string & node_name,
36  const std::string & namespace_,
37  rclcpp::Context::SharedPtr context,
38  const rcl_node_options_t & rcl_node_options,
39  bool use_intra_process_default,
40  bool enable_topic_statistics_default)
41 : context_(context),
42  use_intra_process_default_(use_intra_process_default),
43  enable_topic_statistics_default_(enable_topic_statistics_default),
44  node_handle_(nullptr),
45  default_callback_group_(nullptr),
46  associated_with_executor_(false),
47  notify_guard_condition_(context),
48  notify_guard_condition_is_valid_(false)
49 {
50  // Create the rcl node and store it in a shared_ptr with a custom destructor.
51  std::unique_ptr<rcl_node_t> rcl_node(new rcl_node_t(rcl_get_zero_initialized_node()));
52 
53  std::shared_ptr<std::recursive_mutex> logging_mutex = get_global_logging_mutex();
54 
55  rcl_ret_t ret;
56  {
57  std::lock_guard<std::recursive_mutex> guard(*logging_mutex);
58  // TODO(ivanpauno): /rosout Qos should be reconfigurable.
59  // TODO(ivanpauno): Instead of mutually excluding rcl_node_init with the global logger mutex,
60  // rcl_logging_rosout_init_publisher_for_node could be decoupled from there and be called
61  // here directly.
62  ret = rcl_node_init(
63  rcl_node.get(),
64  node_name.c_str(), namespace_.c_str(),
65  context_->get_rcl_context().get(), &rcl_node_options);
66  }
67  if (ret != RCL_RET_OK) {
68  if (ret == RCL_RET_NODE_INVALID_NAME) {
69  rcl_reset_error(); // discard rcl_node_init error
70  int validation_result;
71  size_t invalid_index;
72  rmw_ret_t rmw_ret =
73  rmw_validate_node_name(node_name.c_str(), &validation_result, &invalid_index);
74  if (rmw_ret != RMW_RET_OK) {
75  if (rmw_ret == RMW_RET_INVALID_ARGUMENT) {
76  throw_from_rcl_error(RCL_RET_INVALID_ARGUMENT, "failed to validate node name");
77  }
78  throw_from_rcl_error(RCL_RET_ERROR, "failed to validate node name");
79  }
80 
81  if (validation_result != RMW_NODE_NAME_VALID) {
83  node_name.c_str(),
84  rmw_node_name_validation_result_string(validation_result),
85  invalid_index);
86  } else {
87  throw std::runtime_error("valid rmw node name but invalid rcl node name");
88  }
89  }
90 
91  if (ret == RCL_RET_NODE_INVALID_NAMESPACE) {
92  rcl_reset_error(); // discard rcl_node_init error
93  int validation_result;
94  size_t invalid_index;
95  rmw_ret_t rmw_ret =
96  rmw_validate_namespace(namespace_.c_str(), &validation_result, &invalid_index);
97  if (rmw_ret != RMW_RET_OK) {
98  if (rmw_ret == RMW_RET_INVALID_ARGUMENT) {
99  throw_from_rcl_error(RCL_RET_INVALID_ARGUMENT, "failed to validate namespace");
100  }
101  throw_from_rcl_error(RCL_RET_ERROR, "failed to validate namespace");
102  }
103 
104  if (validation_result != RMW_NAMESPACE_VALID) {
106  namespace_.c_str(),
107  rmw_namespace_validation_result_string(validation_result),
108  invalid_index);
109  } else {
110  throw std::runtime_error("valid rmw node namespace but invalid rcl node namespace");
111  }
112  }
113  throw_from_rcl_error(ret, "failed to initialize rcl node");
114  }
115 
116  node_handle_.reset(
117  rcl_node.release(),
118  [logging_mutex](rcl_node_t * node) -> void {
119  std::lock_guard<std::recursive_mutex> guard(*logging_mutex);
120  // TODO(ivanpauno): Instead of mutually excluding rcl_node_fini with the global logger mutex,
121  // rcl_logging_rosout_fini_publisher_for_node could be decoupled from there and be called
122  // here directly.
123  if (rcl_node_fini(node) != RCL_RET_OK) {
124  RCUTILS_LOG_ERROR_NAMED(
125  "rclcpp",
126  "Error in destruction of rcl node handle: %s", rcl_get_error_string().str);
127  }
128  delete node;
129  });
130 
131  // Create the default callback group.
132  using rclcpp::CallbackGroupType;
133  default_callback_group_ = create_callback_group(CallbackGroupType::MutuallyExclusive);
134 
135  // Indicate the notify_guard_condition is now valid.
136  notify_guard_condition_is_valid_ = true;
137 }
138 
139 NodeBase::~NodeBase()
140 {
141  // Finalize the interrupt guard condition after removing self from graph listener.
142  {
143  std::lock_guard<std::recursive_mutex> notify_condition_lock(notify_guard_condition_mutex_);
144  notify_guard_condition_is_valid_ = false;
145  }
146 }
147 
148 const char *
150 {
151  return rcl_node_get_name(node_handle_.get());
152 }
153 
154 const char *
156 {
157  return rcl_node_get_namespace(node_handle_.get());
158 }
159 
160 const char *
162 {
163  return rcl_node_get_fully_qualified_name(node_handle_.get());
164 }
165 
166 rclcpp::Context::SharedPtr
168 {
169  return context_;
170 }
171 
172 rcl_node_t *
174 {
175  return node_handle_.get();
176 }
177 
178 const rcl_node_t *
180 {
181  return node_handle_.get();
182 }
183 
184 std::shared_ptr<rcl_node_t>
186 {
187  return std::shared_ptr<rcl_node_t>(shared_from_this(), node_handle_.get());
188 }
189 
190 std::shared_ptr<const rcl_node_t>
192 {
193  return std::shared_ptr<const rcl_node_t>(shared_from_this(), node_handle_.get());
194 }
195 
196 rclcpp::CallbackGroup::SharedPtr
198  rclcpp::CallbackGroupType group_type,
199  bool automatically_add_to_executor_with_node)
200 {
201  auto group = std::make_shared<rclcpp::CallbackGroup>(
202  group_type,
203  automatically_add_to_executor_with_node);
204  std::lock_guard<std::mutex> lock(callback_groups_mutex_);
205  callback_groups_.push_back(group);
206  return group;
207 }
208 
209 rclcpp::CallbackGroup::SharedPtr
211 {
212  return default_callback_group_;
213 }
214 
215 bool
216 NodeBase::callback_group_in_node(rclcpp::CallbackGroup::SharedPtr group)
217 {
218  std::lock_guard<std::mutex> lock(callback_groups_mutex_);
219  for (auto & weak_group : this->callback_groups_) {
220  auto cur_group = weak_group.lock();
221  if (cur_group && (cur_group == group)) {
222  return true;
223  }
224  }
225  return false;
226 }
227 
228 void NodeBase::for_each_callback_group(const CallbackGroupFunction & func)
229 {
230  std::lock_guard<std::mutex> lock(callback_groups_mutex_);
231  for (rclcpp::CallbackGroup::WeakPtr & weak_group : this->callback_groups_) {
232  rclcpp::CallbackGroup::SharedPtr group = weak_group.lock();
233  if (group) {
234  func(group);
235  }
236  }
237 }
238 
239 std::atomic_bool &
241 {
242  return associated_with_executor_;
243 }
244 
247 {
248  std::lock_guard<std::recursive_mutex> notify_condition_lock(notify_guard_condition_mutex_);
249  if (!notify_guard_condition_is_valid_) {
250  throw std::runtime_error("failed to get notify guard condition because it is invalid");
251  }
252  return notify_guard_condition_;
253 }
254 
255 bool
257 {
258  return use_intra_process_default_;
259 }
260 
261 bool
263 {
264  return enable_topic_statistics_default_;
265 }
266 
267 std::string
269  const std::string & name, bool is_service, bool only_expand) const
270 {
271  char * output_cstr = NULL;
272  auto allocator = rcl_get_default_allocator();
274  node_handle_.get(),
275  name.c_str(),
276  allocator,
277  is_service,
278  only_expand,
279  &output_cstr);
280  if (RCL_RET_OK != ret) {
281  throw_from_rcl_error(ret, "failed to resolve name", rcl_get_error_state());
282  }
283  std::string output{output_cstr};
284  allocator.deallocate(output_cstr, allocator.state);
285  return output;
286 }
#define rcl_get_default_allocator
Return a properly initialized rcl_allocator_t with default values.
Definition: allocator.h:37
A condition that can be waited on in a single wait set and asynchronously triggered.
Thrown when a node namespace is invalid.
Definition: exceptions.hpp:78
Thrown when a node name is invalid.
Definition: exceptions.hpp:69
Implementation of the NodeBase part of the Node API.
Definition: node_base.hpp:38
RCLCPP_PUBLIC const char * get_name() const override
Return the name of the node.
Definition: node_base.cpp:149
bool get_enable_topic_statistics_default() const override
Return the default preference for enabling topic statistics collection.
Definition: node_base.cpp:262
RCLCPP_PUBLIC bool get_use_intra_process_default() const override
Return the default preference for using intra process communication.
Definition: node_base.cpp:256
RCLCPP_PUBLIC rclcpp::CallbackGroup::SharedPtr get_default_callback_group() override
Return the default callback group.
Definition: node_base.cpp:210
RCLCPP_PUBLIC rclcpp::CallbackGroup::SharedPtr create_callback_group(rclcpp::CallbackGroupType group_type, bool automatically_add_to_executor_with_node=true) override
Create and return a callback group.
Definition: node_base.cpp:197
RCLCPP_PUBLIC rcl_node_t * get_rcl_node_handle() override
Return the rcl_node_t node handle (non-const version).
Definition: node_base.cpp:173
std::string resolve_topic_or_service_name(const std::string &name, bool is_service, bool only_expand=false) const override
Expand and remap a given topic or service name.
Definition: node_base.cpp:268
RCLCPP_PUBLIC rclcpp::GuardCondition & get_notify_guard_condition() override
Return a guard condition that should be notified when the internal node state changes.
Definition: node_base.cpp:246
RCLCPP_PUBLIC const char * get_namespace() const override
Return the namespace of the node.
Definition: node_base.cpp:155
RCLCPP_PUBLIC std::shared_ptr< rcl_node_t > get_shared_rcl_node_handle() override
Return the rcl_node_t node handle in a std::shared_ptr.
Definition: node_base.cpp:185
RCLCPP_PUBLIC void for_each_callback_group(const CallbackGroupFunction &func) override
Iterate over the stored callback groups, calling the given function on each valid one.
Definition: node_base.cpp:228
RCLCPP_PUBLIC rclcpp::Context::SharedPtr get_context() override
Return the context of the node.
Definition: node_base.cpp:167
RCLCPP_PUBLIC bool callback_group_in_node(rclcpp::CallbackGroup::SharedPtr group) override
Return true if the given callback group is associated with this node.
Definition: node_base.cpp:216
RCLCPP_PUBLIC std::atomic_bool & get_associated_with_executor_atomic() override
Return the atomic bool which is used to ensure only one executor is used.
Definition: node_base.cpp:240
RCLCPP_PUBLIC const char * get_fully_qualified_name() const override
Return the fully qualified name of the node.
Definition: node_base.cpp:161
RCL_PUBLIC RCL_WARN_UNUSED rcl_node_t rcl_get_zero_initialized_node(void)
Return a rcl_node_t struct with members initialized to NULL.
Definition: node.c:107
RCL_PUBLIC RCL_WARN_UNUSED const char * rcl_node_get_name(const rcl_node_t *node)
Return the name of the node.
Definition: node.c:435
RCL_PUBLIC RCL_WARN_UNUSED const char * rcl_node_get_namespace(const rcl_node_t *node)
Return the namespace of the node.
Definition: node.c:444
struct rcl_node_s rcl_node_t
Structure which encapsulates a ROS Node.
RCL_PUBLIC RCL_WARN_UNUSED const char * rcl_node_get_fully_qualified_name(const rcl_node_t *node)
Return the fully qualified name of the node.
Definition: node.c:453
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_node_init(rcl_node_t *node, const char *name, const char *namespace_, rcl_context_t *context, const rcl_node_options_t *options)
Initialize a ROS node.
Definition: node.c:117
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_node_resolve_name(const rcl_node_t *node, const char *input_name, rcl_allocator_t allocator, bool is_service, bool only_expand, char **output_name)
Expand a given name into a fully-qualified topic name and apply remapping rules.
Structure which encapsulates the options for creating a rcl_node_t.
Definition: node_options.h:35
Structure which encapsulates a ROS Node.
Definition: node.h:42
#define RCL_RET_NODE_INVALID_NAMESPACE
Invalid node namespace return code.
Definition: types.h:60
#define RCL_RET_OK
Success return code.
Definition: types.h:26
#define RCL_RET_INVALID_ARGUMENT
Invalid argument return code.
Definition: types.h:34
#define RCL_RET_ERROR
Unspecified error return code.
Definition: types.h:28
#define RCL_RET_NODE_INVALID_NAME
Invalid node name return code.
Definition: types.h:58
rmw_ret_t rcl_ret_t
The type that holds an rcl return code.
Definition: types.h:23