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 
156 [[deprecated("use the function ok() instead, which has the same usage.")]]
158 bool
159 is_initialized(rclcpp::Context::SharedPtr context = nullptr);
160 
162 
176 bool
177 shutdown(
178  rclcpp::Context::SharedPtr context = nullptr,
179  const std::string & reason = "user called rclcpp::shutdown()");
180 
182 
197 void
198 on_shutdown(std::function<void()> callback, rclcpp::Context::SharedPtr context = nullptr);
199 
201 
214 bool
215 sleep_for(
216  const std::chrono::nanoseconds & nanoseconds,
217  rclcpp::Context::SharedPtr context = nullptr);
218 
220 
229 template<typename T>
230 bool
231 add_will_overflow(const T x, const T y)
232 {
233  return (y > 0) && (x > (std::numeric_limits<T>::max() - y));
234 }
235 
237 
246 template<typename T>
247 bool
248 add_will_underflow(const T x, const T y)
249 {
250  return (y < 0) && (x < (std::numeric_limits<T>::min() - y));
251 }
252 
254 
263 template<typename T>
264 bool
265 sub_will_overflow(const T x, const T y)
266 {
267  return (y < 0) && (x > (std::numeric_limits<T>::max() + y));
268 }
269 
271 
280 template<typename T>
281 bool
282 sub_will_underflow(const T x, const T y)
283 {
284  return (y > 0) && (x < (std::numeric_limits<T>::min() + y));
285 }
286 
288 
295 const char *
296 get_c_string(const char * string_in);
297 
299 
304 const char *
305 get_c_string(const std::string & string_in);
306 
307 } // namespace rclcpp
308 
309 #endif // RCLCPP__UTILITIES_HPP_
std::string
rclcpp::sub_will_overflow
bool sub_will_overflow(const T x, const T y)
Safely check if subtraction will overflow.
Definition: utilities.hpp:265
std::vector< std::string >
std::chrono::nanoseconds
context.hpp
std::function
rclcpp::ok
bool ok(rclcpp::Context::SharedPtr context=nullptr)
Check rclcpp's status.
rclcpp
This header provides the get_node_base_interface() template function.
Definition: allocator_common.hpp:24
rclcpp::sleep_for
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.
RCLCPP_PUBLIC
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
rclcpp::init_and_remove_ros_arguments
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.
rclcpp::init
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.
rclcpp::is_initialized
bool is_initialized(rclcpp::Context::SharedPtr context=nullptr)
Return true if init() has already been called for the given context.
rclcpp::add_will_overflow
bool add_will_overflow(const T x, const T y)
Safely check if addition will overflow.
Definition: utilities.hpp:231
rclcpp::sub_will_underflow
bool sub_will_underflow(const T x, const T y)
Safely check if subtraction will underflow.
Definition: utilities.hpp:282
std::to_string
T to_string(T... args)
rclcpp::get_c_string
const char * get_c_string(const char *string_in)
Return the given string.
std::numeric_limits::min
T min(T... args)
std::ostringstream
rclcpp::remove_ros_arguments
std::vector< std::string > remove_ros_arguments(int argc, char const *const argv[])
Remove ROS-specific arguments from argument vector.
rclcpp::install_signal_handlers
bool install_signal_handlers()
Install the global signal handler for rclcpp.
visibility_control.hpp
std
rclcpp::signal_handlers_installed
bool signal_handlers_installed()
Return true if the signal handlers are installed, otherwise false.
rclcpp::uninstall_signal_handlers
bool uninstall_signal_handlers()
Uninstall the global signal handler for rclcpp.
init_options.hpp
std::ostringstream::str
T str(T... args)
rclcpp::on_shutdown
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.
std::numeric_limits::max
T max(T... args)
rclcpp::add_will_underflow
bool add_will_underflow(const T x, const T y)
Safely check if addition will underflow.
Definition: utilities.hpp:248
rclcpp::shutdown
bool shutdown(rclcpp::Context::SharedPtr context=nullptr, const std::string &reason="user called rclcpp::shutdown()")
Shutdown rclcpp context, invalidating it for derived entities.