From 0ba77391166995687ecf7bff2935d09e4b28fbe5 Mon Sep 17 00:00:00 2001 From: Emerson Knapp <537409+emersonknapp@users.noreply.github.com> Date: Tue, 12 Mar 2019 15:32:41 -0700 Subject: [PATCH] Don't hardcode int64_t for duration type representations (#648) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit In LLVM's `libcxx`, `int64_t` doesn't match chrono literals. See example below. To compile, run `clang++-6.0 -stdlib=libc++ -std=c++14 TEST.cpp` ``` using namespace std::chrono_literals; template bool wait_for_service( std::chrono::duration timeout ) { return timeout == std::chrono::nanoseconds(0); } int main() { wait_for_service(2s); return 0; } ``` Result of compilation ``` TEST.cpp:6:1: note: candidate template ignored: could not match 'long' against 'long long' wait_for_service( ``` Signed-off-by: Emerson Knapp Signed-off-by: Steven! Ragnarök --- rclcpp/include/rclcpp/client.hpp | 4 ++-- rclcpp/include/rclcpp/executor.hpp | 12 ++++++------ rclcpp/include/rclcpp/executors.hpp | 18 ++++++++++-------- rclcpp/include/rclcpp/node.hpp | 4 ++-- rclcpp/include/rclcpp/node_impl.hpp | 4 ++-- rclcpp/include/rclcpp/parameter_client.hpp | 8 ++++---- rclcpp_action/include/rclcpp_action/client.hpp | 4 ++-- .../rclcpp_lifecycle/lifecycle_node.hpp | 4 ++-- .../rclcpp_lifecycle/lifecycle_node_impl.hpp | 4 ++-- 9 files changed, 32 insertions(+), 30 deletions(-) diff --git a/rclcpp/include/rclcpp/client.hpp b/rclcpp/include/rclcpp/client.hpp index 1f22b55c6d..46467400fe 100644 --- a/rclcpp/include/rclcpp/client.hpp +++ b/rclcpp/include/rclcpp/client.hpp @@ -78,10 +78,10 @@ class ClientBase bool service_is_ready() const; - template + template bool wait_for_service( - std::chrono::duration timeout = std::chrono::duration(-1)) + std::chrono::duration timeout = std::chrono::duration(-1)) { return wait_for_service_nanoseconds( std::chrono::duration_cast(timeout) diff --git a/rclcpp/include/rclcpp/executor.hpp b/rclcpp/include/rclcpp/executor.hpp index 2de4bdaea4..a87a2d0b1a 100644 --- a/rclcpp/include/rclcpp/executor.hpp +++ b/rclcpp/include/rclcpp/executor.hpp @@ -151,11 +151,11 @@ class Executor * spin_node_once to block indefinitely (the default behavior). A timeout of 0 causes this * function to be non-blocking. */ - template + template void spin_node_once( rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node, - std::chrono::duration timeout = std::chrono::duration(-1)) + std::chrono::duration timeout = std::chrono::duration(-1)) { return spin_node_once_nanoseconds( node, @@ -164,11 +164,11 @@ class Executor } /// Convenience function which takes Node and forwards NodeBaseInterface. - template + template void spin_node_once( std::shared_ptr node, - std::chrono::duration timeout = std::chrono::duration(-1)) + std::chrono::duration timeout = std::chrono::duration(-1)) { return spin_node_once_nanoseconds( node->get_node_base_interface(), @@ -218,11 +218,11 @@ class Executor * code. * \return The return code, one of `SUCCESS`, `INTERRUPTED`, or `TIMEOUT`. */ - template + template FutureReturnCode spin_until_future_complete( std::shared_future & future, - std::chrono::duration timeout = std::chrono::duration(-1)) + std::chrono::duration timeout = std::chrono::duration(-1)) { // TODO(wjwwood): does not work recursively; can't call spin_node_until_future_complete // inside a callback executed by an executor. diff --git a/rclcpp/include/rclcpp/executors.hpp b/rclcpp/include/rclcpp/executors.hpp index af0bdedc00..7417098b1c 100644 --- a/rclcpp/include/rclcpp/executors.hpp +++ b/rclcpp/include/rclcpp/executors.hpp @@ -65,13 +65,13 @@ using rclcpp::executors::SingleThreadedExecutor; * If the time spent inside the blocking loop exceeds this timeout, return a `TIMEOUT` return code. * \return The return code, one of `SUCCESS`, `INTERRUPTED`, or `TIMEOUT`. */ -template +template rclcpp::executor::FutureReturnCode spin_node_until_future_complete( rclcpp::executor::Executor & executor, rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, std::shared_future & future, - std::chrono::duration timeout = std::chrono::duration(-1)) + std::chrono::duration timeout = std::chrono::duration(-1)) { // TODO(wjwwood): does not work recursively; can't call spin_node_until_future_complete // inside a callback executed by an executor. @@ -81,13 +81,14 @@ spin_node_until_future_complete( return retcode; } -template +template rclcpp::executor::FutureReturnCode spin_node_until_future_complete( rclcpp::executor::Executor & executor, std::shared_ptr node_ptr, std::shared_future & future, - std::chrono::duration timeout = std::chrono::duration(-1)) + std::chrono::duration timeout = std::chrono::duration(-1)) { return rclcpp::executors::spin_node_until_future_complete( executor, @@ -98,23 +99,24 @@ spin_node_until_future_complete( } // namespace executors -template +template rclcpp::executor::FutureReturnCode spin_until_future_complete( rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, std::shared_future & future, - std::chrono::duration timeout = std::chrono::duration(-1)) + std::chrono::duration timeout = std::chrono::duration(-1)) { rclcpp::executors::SingleThreadedExecutor executor; return executors::spin_node_until_future_complete(executor, node_ptr, future, timeout); } -template +template rclcpp::executor::FutureReturnCode spin_until_future_complete( std::shared_ptr node_ptr, std::shared_future & future, - std::chrono::duration timeout = std::chrono::duration(-1)) + std::chrono::duration timeout = std::chrono::duration(-1)) { return rclcpp::spin_until_future_complete(node_ptr->get_node_base_interface(), future, timeout); } diff --git a/rclcpp/include/rclcpp/node.hpp b/rclcpp/include/rclcpp/node.hpp index 1f1a24b108..119c25219f 100644 --- a/rclcpp/include/rclcpp/node.hpp +++ b/rclcpp/include/rclcpp/node.hpp @@ -234,10 +234,10 @@ class Node : public std::enable_shared_from_this * \param[in] callback User-defined callback function. * \param[in] group Callback group to execute this timer's callback in. */ - template + template typename rclcpp::WallTimer::SharedPtr create_wall_timer( - std::chrono::duration period, + std::chrono::duration period, CallbackT callback, rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr); diff --git a/rclcpp/include/rclcpp/node_impl.hpp b/rclcpp/include/rclcpp/node_impl.hpp index c584d92b77..a2ef35b9bb 100644 --- a/rclcpp/include/rclcpp/node_impl.hpp +++ b/rclcpp/include/rclcpp/node_impl.hpp @@ -165,10 +165,10 @@ Node::create_subscription( allocator); } -template +template typename rclcpp::WallTimer::SharedPtr Node::create_wall_timer( - std::chrono::duration period, + std::chrono::duration period, CallbackT callback, rclcpp::callback_group::CallbackGroup::SharedPtr group) { diff --git a/rclcpp/include/rclcpp/parameter_client.hpp b/rclcpp/include/rclcpp/parameter_client.hpp index a525c8ef8b..879f261836 100644 --- a/rclcpp/include/rclcpp/parameter_client.hpp +++ b/rclcpp/include/rclcpp/parameter_client.hpp @@ -138,10 +138,10 @@ class AsyncParametersClient bool service_is_ready() const; - template + template bool wait_for_service( - std::chrono::duration timeout = std::chrono::duration(-1)) + std::chrono::duration timeout = std::chrono::duration(-1)) { return wait_for_service_nanoseconds( std::chrono::duration_cast(timeout) @@ -281,10 +281,10 @@ class SyncParametersClient return async_parameters_client_->service_is_ready(); } - template + template bool wait_for_service( - std::chrono::duration timeout = std::chrono::duration(-1)) + std::chrono::duration timeout = std::chrono::duration(-1)) { return async_parameters_client_->wait_for_service(timeout); } diff --git a/rclcpp_action/include/rclcpp_action/client.hpp b/rclcpp_action/include/rclcpp_action/client.hpp index 64837011f3..71839208bf 100644 --- a/rclcpp_action/include/rclcpp_action/client.hpp +++ b/rclcpp_action/include/rclcpp_action/client.hpp @@ -66,10 +66,10 @@ class ClientBase : public rclcpp::Waitable action_server_is_ready() const; /// Wait for action_server_is_ready() to become true, or until the given timeout is reached. - template + template bool wait_for_action_server( - std::chrono::duration timeout = std::chrono::duration(-1)) + std::chrono::duration timeout = std::chrono::duration(-1)) { return wait_for_action_server_nanoseconds( std::chrono::duration_cast(timeout) diff --git a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp index 2c730a7dfb..2e368dac8c 100644 --- a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp +++ b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp @@ -222,10 +222,10 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, * \param[in] callback User-defined callback function. * \param[in] group Callback group to execute this timer's callback in. */ - template + template typename rclcpp::WallTimer::SharedPtr create_wall_timer( - std::chrono::duration period, + std::chrono::duration period, CallbackT callback, rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr); diff --git a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node_impl.hpp b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node_impl.hpp index a351da7645..69d8a48e96 100644 --- a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node_impl.hpp +++ b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node_impl.hpp @@ -132,10 +132,10 @@ LifecycleNode::create_subscription( allocator); } -template +template typename rclcpp::WallTimer::SharedPtr LifecycleNode::create_wall_timer( - std::chrono::duration period, + std::chrono::duration period, CallbackT callback, rclcpp::callback_group::CallbackGroup::SharedPtr group) {