.. _program_listing_file_include_rclcpp_create_timer.hpp: Program Listing for File create_timer.hpp ========================================= |exhale_lsh| :ref:`Return to documentation for file ` (``include/rclcpp/create_timer.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp // Copyright 2019 Open Source Robotics Foundation, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 // // Unless required by applicable law or agreed to in writing, software // distributed under the License is distributed on an "AS IS" BASIS, // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. #ifndef RCLCPP__CREATE_TIMER_HPP_ #define RCLCPP__CREATE_TIMER_HPP_ #include #include #include #include #include #include "rclcpp/duration.hpp" #include "rclcpp/node_interfaces/get_node_base_interface.hpp" #include "rclcpp/node_interfaces/get_node_timers_interface.hpp" #include "rclcpp/node_interfaces/node_base_interface.hpp" #include "rclcpp/node_interfaces/node_timers_interface.hpp" namespace rclcpp { template typename rclcpp::TimerBase::SharedPtr create_timer( std::shared_ptr node_base, std::shared_ptr node_timers, rclcpp::Clock::SharedPtr clock, rclcpp::Duration period, CallbackT && callback, rclcpp::CallbackGroup::SharedPtr group = nullptr) { auto timer = rclcpp::GenericTimer::make_shared( clock, period.to_chrono(), std::forward(callback), node_base->get_context()); node_timers->add_timer(timer, group); return timer; } template typename rclcpp::TimerBase::SharedPtr create_timer( NodeT node, rclcpp::Clock::SharedPtr clock, rclcpp::Duration period, CallbackT && callback, rclcpp::CallbackGroup::SharedPtr group = nullptr) { return create_timer( rclcpp::node_interfaces::get_node_base_interface(node), rclcpp::node_interfaces::get_node_timers_interface(node), clock, period, std::forward(callback), group); } template typename rclcpp::WallTimer::SharedPtr create_wall_timer( std::chrono::duration period, CallbackT callback, rclcpp::CallbackGroup::SharedPtr group, node_interfaces::NodeBaseInterface * node_base, node_interfaces::NodeTimersInterface * node_timers) { if (node_base == nullptr) { throw std::invalid_argument{"input node_base cannot be null"}; } if (node_timers == nullptr) { throw std::invalid_argument{"input node_timers cannot be null"}; } if (period < std::chrono::duration::zero()) { throw std::invalid_argument{"timer period cannot be negative"}; } // Casting to a double representation might lose precision and allow the check below to succeed // but the actual cast to nanoseconds fail. Using 1 DurationT worth of nanoseconds less than max. constexpr auto maximum_safe_cast_ns = std::chrono::nanoseconds::max() - std::chrono::duration(1); // If period is greater than nanoseconds::max(), the duration_cast to nanoseconds will overflow // a signed integer, which is undefined behavior. Checking whether any std::chrono::duration is // greater than nanoseconds::max() is a difficult general problem. This is a more conservative // version of Howard Hinnant's (the guy>) response here: // https://stackoverflow.com/a/44637334/2089061 // However, this doesn't solve the issue for all possible duration types of period. // Follow-up issue: https://github.com/ros2/rclcpp/issues/1177 constexpr auto ns_max_as_double = std::chrono::duration_cast>( maximum_safe_cast_ns); if (period > ns_max_as_double) { throw std::invalid_argument{ "timer period must be less than std::chrono::nanoseconds::max()"}; } const auto period_ns = std::chrono::duration_cast(period); if (period_ns < std::chrono::nanoseconds::zero()) { throw std::runtime_error{ "Casting timer period to nanoseconds resulted in integer overflow."}; } auto timer = rclcpp::WallTimer::make_shared( period_ns, std::move(callback), node_base->get_context()); node_timers->add_timer(timer, group); return timer; } } // namespace rclcpp #endif // RCLCPP__CREATE_TIMER_HPP_