Skip to content
Open
Show file tree
Hide file tree
Changes from 5 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions rclcpp/include/rclcpp/node_interfaces/node_time_source.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,9 @@ class NodeTimeSource : public NodeTimeSourceInterface
bool use_clock_thread = true
);

RCLCPP_PUBLIC
void attachClock(rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock);

RCLCPP_PUBLIC
virtual
~NodeTimeSource();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@

#include "rclcpp/macros.hpp"
#include "rclcpp/node_interfaces/detail/node_interfaces_helpers.hpp"
#include "rclcpp/node_interfaces/node_clock_interface.hpp"
#include "rclcpp/visibility_control.hpp"

namespace rclcpp
Expand All @@ -30,6 +31,10 @@ class NodeTimeSourceInterface
public:
RCLCPP_SMART_PTR_ALIASES_ONLY(NodeTimeSourceInterface)

RCLCPP_PUBLIC
virtual
void attachClock(rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock) = 0;

RCLCPP_PUBLIC
virtual
~NodeTimeSourceInterface() = default;
Expand Down
13 changes: 13 additions & 0 deletions rclcpp/include/rclcpp/node_options.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
#include "rclcpp/publisher_options.hpp"
#include "rclcpp/qos.hpp"
#include "rclcpp/visibility_control.hpp"
#include "rclcpp/node_interfaces/node_time_source_interface.hpp"

namespace rclcpp
{
Expand Down Expand Up @@ -408,6 +409,16 @@ class NodeOptions
NodeOptions &
allocator(rcl_allocator_t allocator);

/// Return the time source to be used.
RCLCPP_PUBLIC
const rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr
time_source() const;

/// Set the time source to be used.
Copy link
Contributor Author

@roncapat roncapat Jun 30, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@fujitatomoya something like this in code?

Suggested change
/// Set the time source to be used.
/// Set the time source to be used.
/**
* This will cause the node to use the provided TimeSource,
* usually obtained by another node. User must understand that
* either the node that owns the TimeSource has to be spinned,
* or `use_clock_thread_` must be configured as `true` on that node.
*/

RCLCPP_PUBLIC
NodeOptions &
time_source(rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr time_source);

private:
// This is mutable to allow for a const accessor which lazily creates the node options instance.
/// Underlying rcl_node_options structure.
Expand Down Expand Up @@ -456,6 +467,8 @@ class NodeOptions
bool automatically_declare_parameters_from_overrides_ {false};

rcl_allocator_t allocator_ {rcl_get_default_allocator()};

rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr time_source_ {nullptr};
};

} // namespace rclcpp
Expand Down
8 changes: 7 additions & 1 deletion rclcpp/src/rclcpp/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -213,7 +213,9 @@ Node::Node(
options.allow_undeclared_parameters(),
options.automatically_declare_parameters_from_overrides()
)),
node_time_source_(new rclcpp::node_interfaces::NodeTimeSource(
node_time_source_(
options.time_source() ? options.time_source() :
std::make_shared<rclcpp::node_interfaces::NodeTimeSource>(
node_base_,
node_topics_,
node_graph_,
Expand All @@ -235,6 +237,10 @@ Node::Node(
sub_namespace_(""),
effective_namespace_(create_effective_namespace(this->get_namespace(), sub_namespace_))
{
// Avoid re-insertion if a TimeSource is not specified via NodeOptions
if (options.time_source()){
node_time_source_->attachClock(node_clock_);
}
// we have got what we wanted directly from the overrides,
// but declare the parameters anyway so they are visible.
rclcpp::detail::declare_qos_parameters(
Expand Down
6 changes: 5 additions & 1 deletion rclcpp/src/rclcpp/node_interfaces/node_time_source.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,11 @@ NodeTimeSource::NodeTimeSource(
node_logging_,
node_clock_,
node_parameters_);
time_source_.attachClock(node_clock_->get_clock());
}

void NodeTimeSource::attachClock(rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock)
{
time_source_.attachClock(clock->get_clock());
}

NodeTimeSource::~NodeTimeSource()
Expand Down
14 changes: 14 additions & 0 deletions rclcpp/src/rclcpp/node_options.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -88,6 +88,7 @@ NodeOptions::operator=(const NodeOptions & other)
this->automatically_declare_parameters_from_overrides_ =
other.automatically_declare_parameters_from_overrides_;
this->allocator_ = other.allocator_;
this->time_source_ = other.time_source_;
}
return *this;
}
Expand Down Expand Up @@ -397,4 +398,17 @@ NodeOptions::allocator(rcl_allocator_t allocator)
return *this;
}

const rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr
NodeOptions::time_source() const
{
return this->time_source_;
}

NodeOptions &
NodeOptions::time_source(rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr time_source)
{
this->time_source_ = time_source;
return *this;
}

} // namespace rclcpp
8 changes: 7 additions & 1 deletion rclcpp/test/rclcpp/test_node_options.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
#include "rcl/arguments.h"
#include "rcl/remap.h"

#include "rclcpp/node.hpp"
#include "rclcpp/node_options.hpp"

#include "../mocking_utils/patch.hpp"
Expand Down Expand Up @@ -210,6 +211,8 @@ TEST(TestNodeOptions, copy) {
// We separate attribute modification from variable initialisation (copy assignment operator)
// to be sure the "non_default_options"'s properties are correctly set before testing the
// assignment operator.
rclcpp::init(0, nullptr);
rclcpp::Node node("time_sink__test_node");
auto non_default_options = rclcpp::NodeOptions();
non_default_options
.parameter_overrides({rclcpp::Parameter("foo", 0), rclcpp::Parameter("bar", "1")})
Expand All @@ -226,7 +229,8 @@ TEST(TestNodeOptions, copy) {
.parameter_event_qos(rclcpp::ClockQoS())
.rosout_qos(rclcpp::ParameterEventsQoS())
.allow_undeclared_parameters(true)
.automatically_declare_parameters_from_overrides(true);
.automatically_declare_parameters_from_overrides(true)
.time_source(node.get_node_time_source_interface());

auto copied_options = non_default_options;
EXPECT_EQ(non_default_options.parameter_overrides(), copied_options.parameter_overrides());
Expand All @@ -250,6 +254,8 @@ TEST(TestNodeOptions, copy) {
copied_options.allow_undeclared_parameters());
EXPECT_EQ(non_default_options.automatically_declare_parameters_from_overrides(),
copied_options.automatically_declare_parameters_from_overrides());
EXPECT_EQ(non_default_options.time_source(), copied_options.time_source());
rclcpp::shutdown();
}
}

Expand Down
8 changes: 7 additions & 1 deletion rclcpp_lifecycle/src/lifecycle_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,9 @@ LifecycleNode::LifecycleNode(
options.allow_undeclared_parameters(),
options.automatically_declare_parameters_from_overrides()
)),
node_time_source_(new rclcpp::node_interfaces::NodeTimeSource(
node_time_source_(
options.time_source() ? options.time_source() :
std::make_shared<rclcpp::node_interfaces::NodeTimeSource>(
node_base_,
node_topics_,
node_graph_,
Expand All @@ -124,6 +126,10 @@ LifecycleNode::LifecycleNode(
node_options_(options),
impl_(new LifecycleNodeInterfaceImpl(node_base_, node_services_, node_logging_))
{
// Avoid re-insertion if a TimeSource is not specified via NodeOptions
if (options.time_source()){
node_time_source_->attachClock(node_clock_);
}
impl_->init(enable_communication_interface);

register_on_configure(
Expand Down