Skip to content

Commit

Permalink
Refactor create_timer to use shared_ptr and follow a predictable call…
Browse files Browse the repository at this point in the history
… sequence

Signed-off-by: Andrew Symington <andrew.c.symington@gmail.com>
  • Loading branch information
asymingt committed Aug 17, 2022
1 parent 74980b4 commit 329ec52
Show file tree
Hide file tree
Showing 12 changed files with 82 additions and 81 deletions.
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/create_generic_publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ std::shared_ptr<GenericPublisher> create_generic_publisher(
{
auto ts_lib = rclcpp::get_typesupport_library(topic_type, "rosidl_typesupport_cpp");
auto pub = std::make_shared<GenericPublisher>(
topics_interface->get_node_base_interface(),
topics_interface->get_node_base_interface().get(),
std::move(ts_lib),
topic_name,
topic_type,
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/create_generic_subscription.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ std::shared_ptr<GenericSubscription> create_generic_subscription(
topic_type, "rosidl_typesupport_cpp");

auto subscription = std::make_shared<GenericSubscription>(
topics_interface->get_node_base_interface(),
topics_interface->get_node_base_interface().get(),
std::move(ts_lib),
topic_name,
topic_type,
Expand Down
4 changes: 1 addition & 3 deletions rclcpp/include/rclcpp/create_subscription.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -105,15 +105,13 @@ create_subscription(
}
};

auto node_timer_interface = node_topics_interface->get_node_timers_interface();

auto timer = create_wall_timer(
std::chrono::duration_cast<std::chrono::nanoseconds>(
options.topic_stats_options.publish_period),
sub_call_back,
options.callback_group,
node_topics_interface->get_node_base_interface(),
node_timer_interface
node_topics_interface->get_node_timers_interface()
);

subscription_topic_stats->set_publisher_timer(timer);
Expand Down
99 changes: 51 additions & 48 deletions rclcpp/include/rclcpp/create_timer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ namespace rclcpp
/// Create a timer with a given clock
/// \internal
template<typename CallbackT>
typename rclcpp::TimerBase::SharedPtr
typename rclcpp::GenericTimer<CallbackT>::SharedPtr
create_timer(
std::shared_ptr<node_interfaces::NodeBaseInterface> node_base,
std::shared_ptr<node_interfaces::NodeTimersInterface> node_timers,
Expand All @@ -43,19 +43,37 @@ create_timer(
CallbackT && callback,
rclcpp::CallbackGroup::SharedPtr group = nullptr)
{
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 clock is not specified, then we want a wall timer by default.
if (clock == nullptr) {
auto timer = rclcpp::WallTimer<CallbackT>::make_shared(
period.to_chrono<std::chrono::nanoseconds>(),
std::forward<CallbackT>(callback),
node_base->get_context());
node_timers->add_timer(timer, group);
return timer;
}

// This is a timer that can be driven by any clock source.
auto timer = rclcpp::GenericTimer<CallbackT>::make_shared(
clock,
period.to_chrono<std::chrono::nanoseconds>(),
std::forward<CallbackT>(callback),
node_base->get_context());

node_timers->add_timer(timer, group);
return timer;
}

/// Create a timer with a given clock
template<typename NodeT, typename CallbackT>
typename rclcpp::TimerBase::SharedPtr
typename rclcpp::GenericTimer<CallbackT>::SharedPtr
create_timer(
NodeT node,
rclcpp::Clock::SharedPtr clock,
Expand Down Expand Up @@ -118,7 +136,7 @@ safe_cast_to_period_in_ns(std::chrono::duration<DurationRepT, DurationT> period)
return period_ns;
}

/// Convenience method to create a wall timer with node resources.
/// Convenience method to create a general timer with node resources.
/**
*
* \tparam DurationRepT
Expand All @@ -129,37 +147,34 @@ safe_cast_to_period_in_ns(std::chrono::duration<DurationRepT, DurationT> period)
* \param group callback group
* \param node_base node base interface
* \param node_timers node timer interface
* \return shared pointer to a wall timer
* \throws std::invalid_argument if either node_base or node_timers
* \return shared pointer to a generic timer
* \throws std::invalid_argument if either node_base, node_timers or node_clock
* are null, or period is negative or too large
*/
template<typename DurationRepT, typename DurationT, typename CallbackT>
typename rclcpp::WallTimer<CallbackT>::SharedPtr
create_wall_timer(
typename rclcpp::GenericTimer<CallbackT>::SharedPtr
create_timer(
std::chrono::duration<DurationRepT, DurationT> period,
CallbackT callback,
rclcpp::CallbackGroup::SharedPtr group,
node_interfaces::NodeBaseInterface * node_base,
node_interfaces::NodeTimersInterface * node_timers)
std::shared_ptr<node_interfaces::NodeBaseInterface> node_base,
std::shared_ptr<node_interfaces::NodeTimersInterface> node_timers,
std::shared_ptr<node_interfaces::NodeClockInterface> node_clock)
{
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 (node_clock == nullptr) {
throw std::invalid_argument{"input node_clock cannot be null"};
}

const std::chrono::nanoseconds period_ns = safe_cast_to_period_in_ns(period);

// Add a new wall timer.
auto timer = rclcpp::WallTimer<CallbackT>::make_shared(
period_ns, std::move(callback), node_base->get_context());
node_timers->add_timer(timer, group);
return timer;
return create_timer(
node_base,
node_timers,
node_clock->get_clock(),
rclcpp::Duration(period_ns),
std::forward<CallbackT>(callback),
group);
}

/// Convenience method to create a general timer with node resources.
/// Convenience method to create a wall timer with node resources.
/**
*
* \tparam DurationRepT
Expand All @@ -170,39 +185,27 @@ create_wall_timer(
* \param group callback group
* \param node_base node base interface
* \param node_timers node timer interface
* \return shared pointer to a generic timer
* \throws std::invalid_argument if either node_base, node_timers or node_clock
* \return shared pointer to a wall timer
* \throws std::invalid_argument if either node_base or node_timers
* are null, or period is negative or too large
*/
template<typename DurationRepT, typename DurationT, typename CallbackT>
typename rclcpp::GenericTimer<CallbackT>::SharedPtr
create_timer(
create_wall_timer(
std::chrono::duration<DurationRepT, DurationT> period,
CallbackT callback,
rclcpp::CallbackGroup::SharedPtr group,
node_interfaces::NodeBaseInterface * node_base,
node_interfaces::NodeTimersInterface * node_timers,
node_interfaces::NodeClockInterface * node_clock)
std::shared_ptr<node_interfaces::NodeBaseInterface> node_base,
std::shared_ptr<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 (node_clock == nullptr) {
throw std::invalid_argument{"input node_clock cannot be null"};
}

const std::chrono::nanoseconds period_ns = safe_cast_to_period_in_ns(period);

// Add a new generic timer.
auto timer = rclcpp::GenericTimer<CallbackT>::make_shared(
node_clock->get_clock(), period_ns, std::move(callback), node_base->get_context());
node_timers->add_timer(timer, group);
return timer;
return create_timer(
node_base,
node_timers,
nullptr,
rclcpp::Duration(period_ns),
std::forward<CallbackT>(callback),
group);
}


Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -234,7 +234,7 @@ class Node : public std::enable_shared_from_this<Node>
* \param[in] group Callback group to execute this timer's callback in.
*/
template<typename DurationRepT = int64_t, typename DurationT = std::milli, typename CallbackT>
typename rclcpp::WallTimer<CallbackT>::SharedPtr
typename rclcpp::GenericTimer<CallbackT>::SharedPtr
create_wall_timer(
std::chrono::duration<DurationRepT, DurationT> period,
CallbackT callback,
Expand Down
12 changes: 6 additions & 6 deletions rclcpp/include/rclcpp/node_impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,7 @@ Node::create_subscription(
}

template<typename DurationRepT, typename DurationT, typename CallbackT>
typename rclcpp::WallTimer<CallbackT>::SharedPtr
typename rclcpp::GenericTimer<CallbackT>::SharedPtr
Node::create_wall_timer(
std::chrono::duration<DurationRepT, DurationT> period,
CallbackT callback,
Expand All @@ -116,8 +116,8 @@ Node::create_wall_timer(
period,
std::move(callback),
group,
this->node_base_.get(),
this->node_timers_.get());
this->node_base_,
this->node_timers_);
}

template<typename DurationRepT, typename DurationT, typename CallbackT>
Expand All @@ -131,9 +131,9 @@ Node::create_timer(
period,
std::move(callback),
group,
this->node_base_.get(),
this->node_timers_.get(),
this->node_clock_.get());
this->node_base_,
this->node_timers_,
this->node_clock_);
}

template<typename ServiceT>
Expand Down
12 changes: 6 additions & 6 deletions rclcpp/include/rclcpp/node_interfaces/node_topics.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,8 +45,8 @@ class NodeTopics : public NodeTopicsInterface

RCLCPP_PUBLIC
NodeTopics(
rclcpp::node_interfaces::NodeBaseInterface * node_base,
rclcpp::node_interfaces::NodeTimersInterface * node_timers);
std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface> node_base,
std::shared_ptr<rclcpp::node_interfaces::NodeTimersInterface> node_timers);

RCLCPP_PUBLIC
~NodeTopics() override;
Expand Down Expand Up @@ -78,11 +78,11 @@ class NodeTopics : public NodeTopicsInterface
rclcpp::CallbackGroup::SharedPtr callback_group) override;

RCLCPP_PUBLIC
rclcpp::node_interfaces::NodeBaseInterface *
std::shared_ptr<node_interfaces::NodeBaseInterface>
get_node_base_interface() const override;

RCLCPP_PUBLIC
rclcpp::node_interfaces::NodeTimersInterface *
std::shared_ptr<rclcpp::node_interfaces::NodeTimersInterface>
get_node_timers_interface() const override;

RCLCPP_PUBLIC
Expand All @@ -92,8 +92,8 @@ class NodeTopics : public NodeTopicsInterface
private:
RCLCPP_DISABLE_COPY(NodeTopics)

rclcpp::node_interfaces::NodeBaseInterface * node_base_;
rclcpp::node_interfaces::NodeTimersInterface * node_timers_;
std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface> node_base_;
std::shared_ptr<rclcpp::node_interfaces::NodeTimersInterface> node_timers_;
};

} // namespace node_interfaces
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -79,12 +79,12 @@ class NodeTopicsInterface

RCLCPP_PUBLIC
virtual
rclcpp::node_interfaces::NodeBaseInterface *
std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>
get_node_base_interface() const = 0;

RCLCPP_PUBLIC
virtual
rclcpp::node_interfaces::NodeTimersInterface *
std::shared_ptr<rclcpp::node_interfaces::NodeTimersInterface>
get_node_timers_interface() const = 0;

/// Get a remapped and expanded topic name given an input name.
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -169,7 +169,7 @@ Node::Node(
node_graph_(new rclcpp::node_interfaces::NodeGraph(node_base_.get())),
node_logging_(new rclcpp::node_interfaces::NodeLogging(node_base_.get())),
node_timers_(new rclcpp::node_interfaces::NodeTimers(node_base_.get())),
node_topics_(new rclcpp::node_interfaces::NodeTopics(node_base_.get(), node_timers_.get())),
node_topics_(new rclcpp::node_interfaces::NodeTopics(node_base_, node_timers_)),
node_services_(new rclcpp::node_interfaces::NodeServices(node_base_.get())),
node_clock_(new rclcpp::node_interfaces::NodeClock(
node_base_,
Expand Down
12 changes: 6 additions & 6 deletions rclcpp/src/rclcpp/node_interfaces/node_topics.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,8 @@ using rclcpp::exceptions::throw_from_rcl_error;
using rclcpp::node_interfaces::NodeTopics;

NodeTopics::NodeTopics(
rclcpp::node_interfaces::NodeBaseInterface * node_base,
rclcpp::node_interfaces::NodeTimersInterface * node_timers)
std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface> node_base,
std::shared_ptr<rclcpp::node_interfaces::NodeTimersInterface> node_timers)
: node_base_(node_base), node_timers_(node_timers)
{}

Expand All @@ -47,7 +47,7 @@ NodeTopics::create_publisher(
const rclcpp::QoS & qos)
{
// Create the MessageT specific Publisher using the factory, but return it as PublisherBase.
return publisher_factory.create_typed_publisher(node_base_, topic_name, qos);
return publisher_factory.create_typed_publisher(node_base_.get(), topic_name, qos);
}

void
Expand Down Expand Up @@ -86,7 +86,7 @@ NodeTopics::create_subscription(
const rclcpp::QoS & qos)
{
// Create the MessageT specific Subscription using the factory, but return a SubscriptionBase.
return subscription_factory.create_typed_subscription(node_base_, topic_name, qos);
return subscription_factory.create_typed_subscription(node_base_.get(), topic_name, qos);
}

void
Expand Down Expand Up @@ -127,13 +127,13 @@ NodeTopics::add_subscription(
}
}

rclcpp::node_interfaces::NodeBaseInterface *
std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>
NodeTopics::get_node_base_interface() const
{
return node_base_;
}

rclcpp::node_interfaces::NodeTimersInterface *
std::shared_ptr<rclcpp::node_interfaces::NodeTimersInterface>
NodeTopics::get_node_timers_interface() const
{
return node_timers_;
Expand Down
10 changes: 5 additions & 5 deletions rclcpp/test/rclcpp/test_create_timer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,9 +69,9 @@ TEST(TestCreateWallTimer, call_wall_timer_with_bad_arguments)
auto callback = []() {};
rclcpp::CallbackGroup::SharedPtr group = nullptr;
auto node_interface =
rclcpp::node_interfaces::get_node_base_interface(node).get();
rclcpp::node_interfaces::get_node_base_interface(node);
auto timers_interface =
rclcpp::node_interfaces::get_node_timers_interface(node).get();
rclcpp::node_interfaces::get_node_timers_interface(node);

// Negative period
EXPECT_THROW(
Expand Down Expand Up @@ -124,11 +124,11 @@ TEST(TestCreateTimer, call_timer_with_bad_arguments)
auto callback = []() {};
rclcpp::CallbackGroup::SharedPtr group = nullptr;
auto node_interface =
rclcpp::node_interfaces::get_node_base_interface(node).get();
rclcpp::node_interfaces::get_node_base_interface(node);
auto timers_interface =
rclcpp::node_interfaces::get_node_timers_interface(node).get();
rclcpp::node_interfaces::get_node_timers_interface(node);
auto clock_interface =
rclcpp::node_interfaces::get_node_clock_interface(node).get();
rclcpp::node_interfaces::get_node_clock_interface(node);

// Negative period
EXPECT_THROW(
Expand Down
2 changes: 1 addition & 1 deletion rclcpp_lifecycle/src/lifecycle_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ LifecycleNode::LifecycleNode(
node_graph_(new rclcpp::node_interfaces::NodeGraph(node_base_.get())),
node_logging_(new rclcpp::node_interfaces::NodeLogging(node_base_.get())),
node_timers_(new rclcpp::node_interfaces::NodeTimers(node_base_.get())),
node_topics_(new rclcpp::node_interfaces::NodeTopics(node_base_.get(), node_timers_.get())),
node_topics_(new rclcpp::node_interfaces::NodeTopics(node_base_, node_timers_)),
node_services_(new rclcpp::node_interfaces::NodeServices(node_base_.get())),
node_clock_(new rclcpp::node_interfaces::NodeClock(
node_base_,
Expand Down

0 comments on commit 329ec52

Please sign in to comment.