File tree Expand file tree Collapse file tree 6 files changed +42
-2
lines changed Expand file tree Collapse file tree 6 files changed +42
-2
lines changed Original file line number Diff line number Diff line change @@ -52,6 +52,9 @@ class NodeTimeSource : public NodeTimeSourceInterface
52
52
bool use_clock_thread = true
53
53
);
54
54
55
+ RCLCPP_PUBLIC
56
+ void attachClock (rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock);
57
+
55
58
RCLCPP_PUBLIC
56
59
virtual
57
60
~NodeTimeSource ();
Original file line number Diff line number Diff line change 17
17
18
18
#include " rclcpp/macros.hpp"
19
19
#include " rclcpp/node_interfaces/detail/node_interfaces_helpers.hpp"
20
+ #include " rclcpp/node_interfaces/node_clock_interface.hpp"
20
21
#include " rclcpp/visibility_control.hpp"
21
22
22
23
namespace rclcpp
@@ -30,6 +31,10 @@ class NodeTimeSourceInterface
30
31
public:
31
32
RCLCPP_SMART_PTR_ALIASES_ONLY (NodeTimeSourceInterface)
32
33
34
+ RCLCPP_PUBLIC
35
+ virtual
36
+ void attachClock (rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock) = 0;
37
+
33
38
RCLCPP_PUBLIC
34
39
virtual
35
40
~NodeTimeSourceInterface () = default ;
Original file line number Diff line number Diff line change 27
27
#include " rclcpp/publisher_options.hpp"
28
28
#include " rclcpp/qos.hpp"
29
29
#include " rclcpp/visibility_control.hpp"
30
+ #include " rclcpp/node_interfaces/node_time_source_interface.hpp"
30
31
31
32
namespace rclcpp
32
33
{
@@ -408,6 +409,16 @@ class NodeOptions
408
409
NodeOptions &
409
410
allocator (rcl_allocator_t allocator);
410
411
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
+
411
422
private:
412
423
// This is mutable to allow for a const accessor which lazily creates the node options instance.
413
424
// / Underlying rcl_node_options structure.
@@ -456,6 +467,8 @@ class NodeOptions
456
467
bool automatically_declare_parameters_from_overrides_ {false };
457
468
458
469
rcl_allocator_t allocator_ {rcl_get_default_allocator ()};
470
+
471
+ rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr time_source_ {nullptr };
459
472
};
460
473
461
474
} // namespace rclcpp
Original file line number Diff line number Diff line change @@ -213,7 +213,8 @@ Node::Node(
213
213
options.allow_undeclared_parameters(),
214
214
options.automatically_declare_parameters_from_overrides()
215
215
)),
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>(
217
218
node_base_,
218
219
node_topics_,
219
220
node_graph_,
@@ -235,6 +236,7 @@ Node::Node(
235
236
sub_namespace_(" " ),
236
237
effective_namespace_(create_effective_namespace(this ->get_namespace (), sub_namespace_))
237
238
{
239
+ node_time_source_->attachClock (node_clock_);
238
240
// we have got what we wanted directly from the overrides,
239
241
// but declare the parameters anyway so they are visible.
240
242
rclcpp::detail::declare_qos_parameters (
Original file line number Diff line number Diff line change @@ -46,7 +46,10 @@ NodeTimeSource::NodeTimeSource(
46
46
node_logging_,
47
47
node_clock_,
48
48
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 ());
50
53
}
51
54
52
55
NodeTimeSource::~NodeTimeSource ()
Original file line number Diff line number Diff line change @@ -88,6 +88,7 @@ NodeOptions::operator=(const NodeOptions & other)
88
88
this ->automatically_declare_parameters_from_overrides_ =
89
89
other.automatically_declare_parameters_from_overrides_ ;
90
90
this ->allocator_ = other.allocator_ ;
91
+ this ->time_source_ = other.time_source_ ;
91
92
}
92
93
return *this ;
93
94
}
@@ -397,4 +398,17 @@ NodeOptions::allocator(rcl_allocator_t allocator)
397
398
return *this ;
398
399
}
399
400
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
+
400
414
} // namespace rclcpp
You can’t perform that action at this time.
0 commit comments