rclcpp  master
C++ ROS Client Library API
utilities.hpp
Go to the documentation of this file.
1 // Copyright 2014 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 #ifndef RCLCPP__UTILITIES_HPP_
16 #define RCLCPP__UTILITIES_HPP_
17 
18 #include <chrono>
19 #include <functional>
20 #include <limits>
21 #include <string>
22 #include <vector>
23 
24 #include "rclcpp/context.hpp"
25 #include "rclcpp/init_options.hpp"
27 
28 #ifdef ANDROID
29 #include <sstream>
30 
31 namespace std
32 {
33 template<typename T>
34 std::string to_string(T value)
35 {
37  os << value;
38  return os.str();
39 }
40 }
41 #endif
42 
43 namespace rclcpp
44 {
46 
55 void
56 init(int argc, char const * const argv[], const InitOptions & init_options = InitOptions());
57 
59 
73 bool
75 
78 bool
80 
82 
95 bool
97 
99 
109  int argc,
110  char const * const argv[],
111  const InitOptions & init_options = InitOptions());
112 
114 
128 remove_ros_arguments(int argc, char const * const argv[]);
129 
131 
143 bool
144 ok(rclcpp::Context::SharedPtr context = nullptr);
145 
147 
157 bool
158 is_initialized(rclcpp::Context::SharedPtr context = nullptr);
159 
161 
174 bool
175 shutdown(
176  rclcpp::Context::SharedPtr context = nullptr,
177  const std::string & reason = "user called rclcpp::shutdown()");
178 
180 
195 void
196 on_shutdown(std::function<void()> callback, rclcpp::Context::SharedPtr context = nullptr);
197 
199 
212 bool
213 sleep_for(
214  const std::chrono::nanoseconds & nanoseconds,
215  rclcpp::Context::SharedPtr context = nullptr);
216 
218 
227 template<typename T>
228 bool
229 add_will_overflow(const T x, const T y)
230 {
231  return (y > 0) && (x > (std::numeric_limits<T>::max() - y));
232 }
233 
235 
244 template<typename T>
245 bool
246 add_will_underflow(const T x, const T y)
247 {
248  return (y < 0) && (x < (std::numeric_limits<T>::min() - y));
249 }
250 
252 
261 template<typename T>
262 bool
263 sub_will_overflow(const T x, const T y)
264 {
265  return (y < 0) && (x > (std::numeric_limits<T>::max() + y));
266 }
267 
269 
278 template<typename T>
279 bool
280 sub_will_underflow(const T x, const T y)
281 {
282  return (y > 0) && (x < (std::numeric_limits<T>::min() + y));
283 }
284 
286 
293 const char *
294 get_c_string(const char * string_in);
295 
297 
302 const char *
303 get_c_string(const std::string & string_in);
304 
305 } // namespace rclcpp
306 
307 #endif // RCLCPP__UTILITIES_HPP_
bool signal_handlers_installed()
Return true if the signal handlers are installed, otherwise false.
bool sub_will_overflow(const T x, const T y)
Safely check if subtraction will overflow.
Definition: utilities.hpp:263
T to_string(T... args)
This header provides the get_node_base_interface() template function.
Definition: allocator_common.hpp:24
bool add_will_underflow(const T x, const T y)
Safely check if addition will underflow.
Definition: utilities.hpp:246
bool shutdown(rclcpp::Context::SharedPtr context=nullptr, const std::string &reason="user called rclcpp::shutdown()")
Shutdown rclcpp context, invalidating it for derived entities.
const char * get_c_string(const std::string &string_in)
Return the C string from the given std::string.
void init(int argc, char const *const argv[], const InitOptions &init_options=InitOptions())
Initialize communications via the rmw implementation and set up a global signal handler.
bool sleep_for(const std::chrono::nanoseconds &nanoseconds, rclcpp::Context::SharedPtr context=nullptr)
Use the global condition variable to block for the specified amount of time.
bool sub_will_underflow(const T x, const T y)
Safely check if subtraction will underflow.
Definition: utilities.hpp:280
bool is_initialized(rclcpp::Context::SharedPtr context=nullptr)
Return true if init() has already been called for the given context.
T str(T... args)
void on_shutdown(std::function< void()> callback, rclcpp::Context::SharedPtr context=nullptr)
Register a function to be called when shutdown is called on the context.
bool add_will_overflow(const T x, const T y)
Safely check if addition will overflow.
Definition: utilities.hpp:229
T max(T... args)
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
Set the data type used in the intra-process buffer as std::shared_ptr<MessageT>
bool ok(rclcpp::Context::SharedPtr context=nullptr)
Check rclcpp&#39;s status.
std::vector< std::string > init_and_remove_ros_arguments(int argc, char const *const argv[], const InitOptions &init_options=InitOptions())
Initialize communications via the rmw implementation and set up a global signal handler.
bool uninstall_signal_handlers()
Uninstall the global signal handler for rclcpp.
std::vector< std::string > remove_ros_arguments(int argc, char const *const argv[])
Remove ROS-specific arguments from argument vector.
bool install_signal_handlers()
Install the global signal handler for rclcpp.