Skip to content

Commit 74c28d0

Browse files
committed
Use a weak_ptr to avoid a potential dangling reference
Signed-off-by: Geoffrey Biggs <gbiggs@killbots.net>
1 parent 8ca0100 commit 74c28d0

1 file changed

Lines changed: 35 additions & 15 deletions

File tree

rclcpp/src/rclcpp/time_source.cpp

Lines changed: 35 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -185,8 +185,8 @@ class TimeSource::ClocksState : public std::enable_shared_from_this<ClocksState>
185185
class TimeSource::NodeState : public std::enable_shared_from_this<NodeState>
186186
{
187187
public:
188-
NodeState(ClocksState & clocks_state, const rclcpp::QoS & qos, bool use_clock_thread)
189-
: clocks_state_(clocks_state),
188+
NodeState(std::weak_ptr<ClocksState> clocks_state, const rclcpp::QoS & qos, bool use_clock_thread)
189+
: clocks_state_(std::move(clocks_state)),
190190
use_clock_thread_(use_clock_thread),
191191
logger_(rclcpp::get_logger("rclcpp")),
192192
qos_(qos)
@@ -258,8 +258,12 @@ class TimeSource::NodeState : public std::enable_shared_from_this<NodeState>
258258
if (use_sim_time_param.get_type() == rclcpp::PARAMETER_BOOL) {
259259
if (use_sim_time_param.get<bool>()) {
260260
parameter_state_ = SET_TRUE;
261-
clocks_state_.enable_ros_time();
262-
create_clock_sub();
261+
// There should be no way to call this attachNode when the clocks_state_ pointer is not
262+
// valid because it means the TimeSource is being destroyed
263+
if (auto clocks_state_ptr = clocks_state_.lock()) {
264+
clocks_state_ptr->enable_ros_time();
265+
create_clock_sub();
266+
}
263267
}
264268
} else {
265269
RCLCPP_ERROR(
@@ -299,7 +303,11 @@ class TimeSource::NodeState : public std::enable_shared_from_this<NodeState>
299303
// Detach the attached node
300304
void detachNode()
301305
{
302-
clocks_state_.disable_ros_time();
306+
// There should be no way to call detachNode when the clocks_state_ pointer is not valid
307+
// because it means the TimeSource is being destroyed
308+
if (auto clocks_state_ptr = clocks_state_.lock()) {
309+
clocks_state_ptr->disable_ros_time();
310+
}
303311
destroy_clock_sub();
304312
parameter_subscription_.reset();
305313
node_base_.reset();
@@ -316,7 +324,7 @@ class TimeSource::NodeState : public std::enable_shared_from_this<NodeState>
316324
}
317325

318326
private:
319-
ClocksState & clocks_state_;
327+
std::weak_ptr<ClocksState> clocks_state_;
320328

321329
// Dedicated thread for clock subscription.
322330
bool use_clock_thread_;
@@ -350,15 +358,21 @@ class TimeSource::NodeState : public std::enable_shared_from_this<NodeState>
350358
// The clock callback itself
351359
void clock_cb(std::shared_ptr<const rosgraph_msgs::msg::Clock> msg)
352360
{
353-
if (!clocks_state_.is_ros_time_active() && SET_TRUE == this->parameter_state_) {
354-
clocks_state_.enable_ros_time();
361+
auto clocks_state_ptr = clocks_state_.lock();
362+
if (!clocks_state_ptr) {
363+
// The clock_state_ pointer is no longer valid, implying that the TimeSource object is being
364+
// destroyed, so do nothing
365+
return;
366+
}
367+
if (!clocks_state_ptr->is_ros_time_active() && SET_TRUE == this->parameter_state_) {
368+
clocks_state_ptr->enable_ros_time();
355369
}
356370
// Cache the last message in case a new clock is attached.
357-
clocks_state_.cache_last_msg(msg);
371+
clocks_state_ptr->cache_last_msg(msg);
358372
auto time_msg = std::make_shared<builtin_interfaces::msg::Time>(msg->clock);
359373

360374
if (SET_TRUE == this->parameter_state_) {
361-
clocks_state_.set_all_clocks(time_msg, true);
375+
clocks_state_ptr->set_all_clocks(time_msg, true);
362376
}
363377
}
364378

@@ -440,6 +454,12 @@ class TimeSource::NodeState : public std::enable_shared_from_this<NodeState>
440454
// Callback for parameter updates
441455
void on_parameter_event(std::shared_ptr<const rcl_interfaces::msg::ParameterEvent> event)
442456
{
457+
auto clocks_state_ptr = clocks_state_.lock();
458+
if (!clocks_state_ptr) {
459+
// The clock_state_ pointer is no longer valid, implying that the TimeSource object is being
460+
// destroyed, so do nothing
461+
return;
462+
}
443463
// Filter out events on 'use_sim_time' parameter instances in other nodes.
444464
if (event->node != node_base_->get_fully_qualified_name()) {
445465
return;
@@ -455,11 +475,11 @@ class TimeSource::NodeState : public std::enable_shared_from_this<NodeState>
455475
}
456476
if (it.second->value.bool_value) {
457477
parameter_state_ = SET_TRUE;
458-
clocks_state_.enable_ros_time();
478+
clocks_state_ptr->enable_ros_time();
459479
create_clock_sub();
460480
} else {
461481
parameter_state_ = SET_FALSE;
462-
clocks_state_.disable_ros_time();
482+
clocks_state_ptr->disable_ros_time();
463483
destroy_clock_sub();
464484
}
465485
}
@@ -489,7 +509,7 @@ TimeSource::TimeSource(
489509
constructed_qos_(qos)
490510
{
491511
clocks_state_ = std::make_shared<ClocksState>();
492-
node_state_ = std::make_shared<NodeState>(*clocks_state_, qos, use_clock_thread);
512+
node_state_ = std::make_shared<NodeState>(clocks_state_->weak_from_this(), qos, use_clock_thread);
493513
attachNode(node);
494514
}
495515

@@ -500,7 +520,7 @@ TimeSource::TimeSource(
500520
constructed_qos_(qos)
501521
{
502522
clocks_state_ = std::make_shared<ClocksState>();
503-
node_state_ = std::make_shared<NodeState>(*clocks_state_, qos, use_clock_thread);
523+
node_state_ = std::make_shared<NodeState>(clocks_state_->weak_from_this(), qos, use_clock_thread);
504524
}
505525

506526
void TimeSource::attachNode(rclcpp::Node::SharedPtr node)
@@ -539,7 +559,7 @@ void TimeSource::detachNode()
539559
{
540560
node_state_.reset();
541561
node_state_ = std::make_shared<NodeState>(
542-
*clocks_state_,
562+
clocks_state_->weak_from_this(),
543563
constructed_qos_,
544564
constructed_use_clock_thread_);
545565
}

0 commit comments

Comments
 (0)