Skip to content

Commit 623ed83

Browse files
committed
Allow to pass existing TimeSource via NodeOptions
Signed-off-by: Patrick Roncagliolo <ronca.pat@gmail.com>
1 parent 88ebea9 commit 623ed83

File tree

6 files changed

+42
-2
lines changed

6 files changed

+42
-2
lines changed

rclcpp/include/rclcpp/node_interfaces/node_time_source.hpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -52,6 +52,9 @@ class NodeTimeSource : public NodeTimeSourceInterface
5252
bool use_clock_thread = true
5353
);
5454

55+
RCLCPP_PUBLIC
56+
void attachClock(rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock);
57+
5558
RCLCPP_PUBLIC
5659
virtual
5760
~NodeTimeSource();

rclcpp/include/rclcpp/node_interfaces/node_time_source_interface.hpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717

1818
#include "rclcpp/macros.hpp"
1919
#include "rclcpp/node_interfaces/detail/node_interfaces_helpers.hpp"
20+
#include "rclcpp/node_interfaces/node_clock_interface.hpp"
2021
#include "rclcpp/visibility_control.hpp"
2122

2223
namespace rclcpp
@@ -30,6 +31,10 @@ class NodeTimeSourceInterface
3031
public:
3132
RCLCPP_SMART_PTR_ALIASES_ONLY(NodeTimeSourceInterface)
3233

34+
RCLCPP_PUBLIC
35+
virtual
36+
void attachClock(rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock) = 0;
37+
3338
RCLCPP_PUBLIC
3439
virtual
3540
~NodeTimeSourceInterface() = default;

rclcpp/include/rclcpp/node_options.hpp

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,7 @@
2727
#include "rclcpp/publisher_options.hpp"
2828
#include "rclcpp/qos.hpp"
2929
#include "rclcpp/visibility_control.hpp"
30+
#include "rclcpp/node_interfaces/node_time_source_interface.hpp"
3031

3132
namespace rclcpp
3233
{
@@ -408,6 +409,16 @@ class NodeOptions
408409
NodeOptions &
409410
allocator(rcl_allocator_t allocator);
410411

412+
/// Return the time source to be used.
413+
RCLCPP_PUBLIC
414+
const rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr
415+
time_source() const;
416+
417+
/// Set the time source to be used.
418+
RCLCPP_PUBLIC
419+
NodeOptions &
420+
time_source(rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr time_source);
421+
411422
private:
412423
// This is mutable to allow for a const accessor which lazily creates the node options instance.
413424
/// Underlying rcl_node_options structure.
@@ -456,6 +467,8 @@ class NodeOptions
456467
bool automatically_declare_parameters_from_overrides_ {false};
457468

458469
rcl_allocator_t allocator_ {rcl_get_default_allocator()};
470+
471+
rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr time_source_ {nullptr};
459472
};
460473

461474
} // namespace rclcpp

rclcpp/src/rclcpp/node.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -213,7 +213,8 @@ Node::Node(
213213
options.allow_undeclared_parameters(),
214214
options.automatically_declare_parameters_from_overrides()
215215
)),
216-
node_time_source_(new rclcpp::node_interfaces::NodeTimeSource(
216+
node_time_source_(
217+
options.time_source() ? options.time_source() : std::make_shared<rclcpp::node_interfaces::NodeTimeSource>(
217218
node_base_,
218219
node_topics_,
219220
node_graph_,
@@ -235,6 +236,7 @@ Node::Node(
235236
sub_namespace_(""),
236237
effective_namespace_(create_effective_namespace(this->get_namespace(), sub_namespace_))
237238
{
239+
node_time_source_->attachClock(node_clock_);
238240
// we have got what we wanted directly from the overrides,
239241
// but declare the parameters anyway so they are visible.
240242
rclcpp::detail::declare_qos_parameters(

rclcpp/src/rclcpp/node_interfaces/node_time_source.cpp

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -46,7 +46,10 @@ NodeTimeSource::NodeTimeSource(
4646
node_logging_,
4747
node_clock_,
4848
node_parameters_);
49-
time_source_.attachClock(node_clock_->get_clock());
49+
}
50+
51+
void NodeTimeSource::attachClock(rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock){
52+
time_source_.attachClock(clock->get_clock());
5053
}
5154

5255
NodeTimeSource::~NodeTimeSource()

rclcpp/src/rclcpp/node_options.cpp

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -88,6 +88,7 @@ NodeOptions::operator=(const NodeOptions & other)
8888
this->automatically_declare_parameters_from_overrides_ =
8989
other.automatically_declare_parameters_from_overrides_;
9090
this->allocator_ = other.allocator_;
91+
this->time_source_ = other.time_source_;
9192
}
9293
return *this;
9394
}
@@ -397,4 +398,17 @@ NodeOptions::allocator(rcl_allocator_t allocator)
397398
return *this;
398399
}
399400

401+
const rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr
402+
NodeOptions::time_source() const
403+
{
404+
return this->time_source_;
405+
}
406+
407+
NodeOptions &
408+
NodeOptions::time_source(rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr time_source)
409+
{
410+
this->time_source_ = time_source;
411+
return *this;
412+
}
413+
400414
} // namespace rclcpp

0 commit comments

Comments
 (0)