Skip to content

Commit

Permalink
Don't hardcode int64_t for duration type representations (ros2#648)
Browse files Browse the repository at this point in the history
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<typename RatioT = std::milli>
bool
wait_for_service(
   std::chrono::duration<int64_t, RatioT> 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 <eknapp@amazon.com>
Signed-off-by: Steven! Ragnarök <steven@nuclearsandwich.com>
  • Loading branch information
emersonknapp authored and mobangjack committed Apr 24, 2021
1 parent 35064a1 commit d42efca
Show file tree
Hide file tree
Showing 8 changed files with 30 additions and 28 deletions.
4 changes: 2 additions & 2 deletions rclcpp/include/rclcpp/client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,10 +78,10 @@ class ClientBase
bool
service_is_ready() const;

template<typename RatioT = std::milli>
template<typename RepT = int64_t, typename RatioT = std::milli>
bool
wait_for_service(
std::chrono::duration<int64_t, RatioT> timeout = std::chrono::duration<int64_t, RatioT>(-1))
std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
{
return wait_for_service_nanoseconds(
std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
Expand Down
12 changes: 6 additions & 6 deletions rclcpp/include/rclcpp/executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -146,11 +146,11 @@ class Executor
* spin_node_once to block indefinitely (the default behavior). A timeout of 0 causes this
* function to be non-blocking.
*/
template<typename T = std::milli>
template<typename RepT = int64_t, typename T = std::milli>
void
spin_node_once(
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node,
std::chrono::duration<int64_t, T> timeout = std::chrono::duration<int64_t, T>(-1))
std::chrono::duration<RepT, T> timeout = std::chrono::duration<RepT, T>(-1))
{
return spin_node_once_nanoseconds(
node,
Expand All @@ -159,11 +159,11 @@ class Executor
}

/// Convenience function which takes Node and forwards NodeBaseInterface.
template<typename NodeT = rclcpp::Node, typename T = std::milli>
template<typename NodeT = rclcpp::Node, typename RepT = int64_t, typename T = std::milli>
void
spin_node_once(
std::shared_ptr<NodeT> node,
std::chrono::duration<int64_t, T> timeout = std::chrono::duration<int64_t, T>(-1))
std::chrono::duration<RepT, T> timeout = std::chrono::duration<RepT, T>(-1))
{
return spin_node_once_nanoseconds(
node->get_node_base_interface(),
Expand Down Expand Up @@ -209,11 +209,11 @@ class Executor
* code.
* \return The return code, one of `SUCCESS`, `INTERRUPTED`, or `TIMEOUT`.
*/
template<typename ResponseT, typename TimeT = std::milli>
template<typename ResponseT, typename TimeRepT = int64_t, typename TimeT = std::milli>
FutureReturnCode
spin_until_future_complete(
std::shared_future<ResponseT> & future,
std::chrono::duration<int64_t, TimeT> timeout = std::chrono::duration<int64_t, TimeT>(-1))
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
{
// TODO(wjwwood): does not work recursively; can't call spin_node_until_future_complete
// inside a callback executed by an executor.
Expand Down
18 changes: 10 additions & 8 deletions rclcpp/include/rclcpp/executors.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<typename ResponseT, typename TimeT = std::milli>
template<typename ResponseT, typename TimeRepT = int64_t, typename TimeT = std::milli>
rclcpp::executor::FutureReturnCode
spin_node_until_future_complete(
rclcpp::executor::Executor & executor,
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
std::shared_future<ResponseT> & future,
std::chrono::duration<int64_t, TimeT> timeout = std::chrono::duration<int64_t, TimeT>(-1))
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
{
// TODO(wjwwood): does not work recursively; can't call spin_node_until_future_complete
// inside a callback executed by an executor.
Expand All @@ -81,13 +81,14 @@ spin_node_until_future_complete(
return retcode;
}

template<typename NodeT = rclcpp::Node, typename ResponseT, typename TimeT = std::milli>
template<typename NodeT = rclcpp::Node, typename ResponseT, typename TimeRepT = int64_t,
typename TimeT = std::milli>
rclcpp::executor::FutureReturnCode
spin_node_until_future_complete(
rclcpp::executor::Executor & executor,
std::shared_ptr<NodeT> node_ptr,
std::shared_future<ResponseT> & future,
std::chrono::duration<int64_t, TimeT> timeout = std::chrono::duration<int64_t, TimeT>(-1))
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
{
return rclcpp::executors::spin_node_until_future_complete(
executor,
Expand All @@ -98,23 +99,24 @@ spin_node_until_future_complete(

} // namespace executors

template<typename FutureT, typename TimeT = std::milli>
template<typename FutureT, typename TimeRepT = int64_t, typename TimeT = std::milli>
rclcpp::executor::FutureReturnCode
spin_until_future_complete(
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
std::shared_future<FutureT> & future,
std::chrono::duration<int64_t, TimeT> timeout = std::chrono::duration<int64_t, TimeT>(-1))
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
{
rclcpp::executors::SingleThreadedExecutor executor;
return executors::spin_node_until_future_complete<FutureT>(executor, node_ptr, future, timeout);
}

template<typename NodeT = rclcpp::Node, typename FutureT, typename TimeT = std::milli>
template<typename NodeT = rclcpp::Node, typename FutureT, typename TimeRepT = int64_t,
typename TimeT = std::milli>
rclcpp::executor::FutureReturnCode
spin_until_future_complete(
std::shared_ptr<NodeT> node_ptr,
std::shared_future<FutureT> & future,
std::chrono::duration<int64_t, TimeT> timeout = std::chrono::duration<int64_t, TimeT>(-1))
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
{
return rclcpp::spin_until_future_complete(node_ptr->get_node_base_interface(), future, timeout);
}
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -237,10 +237,10 @@ class Node : public std::enable_shared_from_this<Node>
* \param[in] callback User-defined callback function.
* \param[in] group Callback group to execute this timer's callback in.
*/
template<typename DurationT = std::milli, typename CallbackT>
template<typename DurationRepT = int64_t, typename DurationT = std::milli, typename CallbackT>
typename rclcpp::WallTimer<CallbackT>::SharedPtr
create_wall_timer(
std::chrono::duration<int64_t, DurationT> period,
std::chrono::duration<DurationRepT, DurationT> period,
CallbackT callback,
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr);

Expand Down
4 changes: 2 additions & 2 deletions rclcpp/include/rclcpp/node_impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -151,10 +151,10 @@ Node::create_subscription(
allocator);
}

template<typename DurationT, typename CallbackT>
template<typename DurationRepT, typename DurationT, typename CallbackT>
typename rclcpp::WallTimer<CallbackT>::SharedPtr
Node::create_wall_timer(
std::chrono::duration<int64_t, DurationT> period,
std::chrono::duration<DurationRepT, DurationT> period,
CallbackT callback,
rclcpp::callback_group::CallbackGroup::SharedPtr group)
{
Expand Down
8 changes: 4 additions & 4 deletions rclcpp/include/rclcpp/parameter_client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -138,10 +138,10 @@ class AsyncParametersClient
bool
service_is_ready() const;

template<typename RatioT = std::milli>
template<typename RepT = int64_t, typename RatioT = std::milli>
bool
wait_for_service(
std::chrono::duration<int64_t, RatioT> timeout = std::chrono::duration<int64_t, RatioT>(-1))
std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
{
return wait_for_service_nanoseconds(
std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
Expand Down Expand Up @@ -258,10 +258,10 @@ class SyncParametersClient
return async_parameters_client_->service_is_ready();
}

template<typename RatioT = std::milli>
template<typename RepT = int64_t, typename RatioT = std::milli>
bool
wait_for_service(
std::chrono::duration<int64_t, RatioT> timeout = std::chrono::duration<int64_t, RatioT>(-1))
std::chrono::duration<RepT, RatioT> timeout = std::chrono::duration<RepT, RatioT>(-1))
{
return async_parameters_client_->wait_for_service(timeout);
}
Expand Down
4 changes: 2 additions & 2 deletions rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -229,10 +229,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<typename DurationT = std::milli, typename CallbackT>
template<typename DurationRepT = int64_t, typename DurationT = std::milli, typename CallbackT>
typename rclcpp::WallTimer<CallbackT>::SharedPtr
create_wall_timer(
std::chrono::duration<int64_t, DurationT> period,
std::chrono::duration<DurationRepT, DurationT> period,
CallbackT callback,
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -132,10 +132,10 @@ LifecycleNode::create_subscription(
allocator);
}

template<typename DurationT, typename CallbackT>
template<typename DurationRepT, typename DurationT, typename CallbackT>
typename rclcpp::WallTimer<CallbackT>::SharedPtr
LifecycleNode::create_wall_timer(
std::chrono::duration<int64_t, DurationT> period,
std::chrono::duration<DurationRepT, DurationT> period,
CallbackT callback,
rclcpp::callback_group::CallbackGroup::SharedPtr group)
{
Expand Down

0 comments on commit d42efca

Please sign in to comment.