Skip to content

Commit

Permalink
construct TimerBase/GenericTimer with Clock (#523)
Browse files Browse the repository at this point in the history
* construct TimerBase/GenericTimer with Clock

* pass rcl_time_point_value_t to rcl_clock_get_now

* update docblocks
  • Loading branch information
dirk-thomas committed Jul 28, 2018
1 parent fba891c commit 4ddb76f
Show file tree
Hide file tree
Showing 5 changed files with 49 additions and 15 deletions.
4 changes: 4 additions & 0 deletions rclcpp/include/rclcpp/clock.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -99,6 +99,10 @@ class Clock
bool
ros_time_is_active();

RCLCPP_PUBLIC
rcl_clock_t *
get_clock_handle();

RCLCPP_PUBLIC
rcl_clock_type_t
get_clock_type();
Expand Down
43 changes: 32 additions & 11 deletions rclcpp/include/rclcpp/timer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
#include <type_traits>
#include <utility>

#include "rclcpp/clock.hpp"
#include "rclcpp/function_traits.hpp"
#include "rclcpp/macros.hpp"
#include "rclcpp/rate.hpp"
Expand All @@ -44,7 +45,7 @@ class TimerBase
RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(TimerBase)

RCLCPP_PUBLIC
explicit TimerBase(std::chrono::nanoseconds period);
explicit TimerBase(Clock::SharedPtr clock, std::chrono::nanoseconds period);

RCLCPP_PUBLIC
~TimerBase();
Expand Down Expand Up @@ -85,21 +86,20 @@ class TimerBase
bool is_ready();

protected:
Clock::SharedPtr clock_;
std::shared_ptr<rcl_timer_t> timer_handle_;
};


using VoidCallbackType = std::function<void ()>;
using TimerCallbackType = std::function<void (TimerBase &)>;

/// Generic timer templated on the clock type. Periodically executes a user-specified callback.
/// Generic timer. Periodically executes a user-specified callback.
template<
typename FunctorT,
class Clock,
typename std::enable_if<
(rclcpp::function_traits::same_arguments<FunctorT, VoidCallbackType>::value ||
rclcpp::function_traits::same_arguments<FunctorT, TimerCallbackType>::value) &&
Clock::is_steady
rclcpp::function_traits::same_arguments<FunctorT, VoidCallbackType>::value ||
rclcpp::function_traits::same_arguments<FunctorT, TimerCallbackType>::value
>::type * = nullptr
>
class GenericTimer : public TimerBase
Expand All @@ -109,11 +109,14 @@ class GenericTimer : public TimerBase

/// Default constructor.
/**
* \param[in] clock The clock providing the current time.
* \param[in] period The interval at which the timer fires.
* \param[in] callback User-specified callback function.
*/
GenericTimer(std::chrono::nanoseconds period, FunctorT && callback)
: TimerBase(period), callback_(std::forward<FunctorT>(callback))
explicit GenericTimer(
Clock::SharedPtr clock, std::chrono::nanoseconds period, FunctorT && callback
)
: TimerBase(clock, period), callback_(std::forward<FunctorT>(callback))
{
}

Expand Down Expand Up @@ -165,7 +168,7 @@ class GenericTimer : public TimerBase
virtual bool
is_steady()
{
return Clock::is_steady;
return clock_->get_clock_type() == RCL_STEADY_TIME;
}

protected:
Expand All @@ -174,8 +177,26 @@ class GenericTimer : public TimerBase
FunctorT callback_;
};

template<typename CallbackType>
using WallTimer = GenericTimer<CallbackType, std::chrono::steady_clock>;
template<
typename FunctorT,
typename std::enable_if<
rclcpp::function_traits::same_arguments<FunctorT, VoidCallbackType>::value ||
rclcpp::function_traits::same_arguments<FunctorT, TimerCallbackType>::value
>::type * = nullptr
>
class WallTimer : public GenericTimer<FunctorT>
{
public:
RCLCPP_SMART_PTR_DEFINITIONS(WallTimer)

explicit WallTimer(std::chrono::nanoseconds period, FunctorT && callback)
: GenericTimer<FunctorT>(
std::make_shared<Clock>(RCL_STEADY_TIME), period, std::move(callback))
{}

protected:
RCLCPP_DISABLE_COPY(WallTimer)
};

} // namespace rclcpp

Expand Down
8 changes: 7 additions & 1 deletion rclcpp/src/rclcpp/clock.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ Clock::now()
{
Time now(0, 0, rcl_clock_.type);

auto ret = rcl_clock_get_now(&rcl_clock_, &now.rcl_time_);
auto ret = rcl_clock_get_now(&rcl_clock_, &now.rcl_time_.nanoseconds);
if (ret != RCL_RET_OK) {
rclcpp::exceptions::throw_from_rcl_error(
ret, "could not get current time stamp");
Expand All @@ -103,6 +103,12 @@ Clock::ros_time_is_active()
return is_enabled;
}

rcl_clock_t *
Clock::get_clock_handle()
{
return &rcl_clock_;
}

rcl_clock_type_t
Clock::get_clock_type()
{
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/time_source.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ void TimeSource::attachNode(
node_services_ = node_services_interface;
// TODO(tfoote): Update QOS

const std::string & topic_name = "/clock";
const std::string topic_name = "/clock";

rclcpp::callback_group::CallbackGroup::SharedPtr group;
using rclcpp::message_memory_strategy::MessageMemoryStrategy;
Expand Down
7 changes: 5 additions & 2 deletions rclcpp/src/rclcpp/timer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,10 @@

using rclcpp::TimerBase;

TimerBase::TimerBase(std::chrono::nanoseconds period)
TimerBase::TimerBase(rclcpp::Clock::SharedPtr clock, std::chrono::nanoseconds period)
{
clock_ = clock;

timer_handle_ = std::shared_ptr<rcl_timer_t>(
new rcl_timer_t, [ = ](rcl_timer_t * timer)
{
Expand All @@ -38,8 +40,9 @@ TimerBase::TimerBase(std::chrono::nanoseconds period)

*timer_handle_.get() = rcl_get_zero_initialized_timer();

rcl_clock_t * clock_handle = clock_->get_clock_handle();
if (rcl_timer_init(
timer_handle_.get(), period.count(), nullptr,
timer_handle_.get(), clock_handle, period.count(), nullptr,
rcl_get_default_allocator()) != RCL_RET_OK)
{
RCUTILS_LOG_ERROR_NAMED(
Expand Down

0 comments on commit 4ddb76f

Please sign in to comment.