Don't hardcode int64_t for duration type representations (#648)
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>
This commit is contained in:
parent
fce1d4b86f
commit
83beaf8a3f
9 changed files with 32 additions and 30 deletions
|
@ -78,10 +78,10 @@ public:
|
|||
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)
|
||||
|
|
|
@ -151,11 +151,11 @@ public:
|
|||
* 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,
|
||||
|
@ -164,11 +164,11 @@ public:
|
|||
}
|
||||
|
||||
/// 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(),
|
||||
|
@ -218,11 +218,11 @@ public:
|
|||
* 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.
|
||||
|
|
|
@ -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.
|
||||
|
@ -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,
|
||||
|
@ -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);
|
||||
}
|
||||
|
|
|
@ -234,10 +234,10 @@ public:
|
|||
* \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);
|
||||
|
||||
|
|
|
@ -165,10 +165,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)
|
||||
{
|
||||
|
|
|
@ -138,10 +138,10 @@ public:
|
|||
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)
|
||||
|
@ -281,10 +281,10 @@ public:
|
|||
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);
|
||||
}
|
||||
|
|
|
@ -66,10 +66,10 @@ public:
|
|||
action_server_is_ready() const;
|
||||
|
||||
/// Wait for action_server_is_ready() to become true, or until the given timeout is reached.
|
||||
template<typename RatioT = std::milli>
|
||||
template<typename RepT = int64_t, typename RatioT = std::milli>
|
||||
bool
|
||||
wait_for_action_server(
|
||||
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_action_server_nanoseconds(
|
||||
std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
|
||||
|
|
|
@ -222,10 +222,10 @@ public:
|
|||
* \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);
|
||||
|
||||
|
|
|
@ -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)
|
||||
{
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue