File tree 2 files changed +9
-9
lines changed
common/autoware_universe_utils
include/autoware/universe_utils/system
2 files changed +9
-9
lines changed Original file line number Diff line number Diff line change @@ -67,9 +67,9 @@ class ProcessingTimeNode : public std::enable_shared_from_this<ProcessingTimeNod
67
67
/* *
68
68
* @brief Get the parent node
69
69
*
70
- * @return std::shared_ptr <ProcessingTimeNode> Shared pointer to the parent node
70
+ * @return std::weak_ptr <ProcessingTimeNode> Weak pointer to the parent node
71
71
*/
72
- std::shared_ptr <ProcessingTimeNode> get_parent_node () const ;
72
+ std::weak_ptr <ProcessingTimeNode> get_parent_node () const ;
73
73
74
74
/* *
75
75
* @brief Get the child nodes
@@ -101,10 +101,10 @@ class ProcessingTimeNode : public std::enable_shared_from_this<ProcessingTimeNod
101
101
std::string get_name () const ;
102
102
103
103
private:
104
- const std::string name_; // !< Name of the node
105
- double processing_time_{0.0 }; // !< Processing time of the node
106
- std::string comment_; // !< Comment for the node
107
- std::shared_ptr <ProcessingTimeNode> parent_node_{ nullptr } ; // !< Shared pointer to the parent node
104
+ const std::string name_; // !< Name of the node
105
+ double processing_time_{0.0 }; // !< Processing time of the node
106
+ std::string comment_; // !< Comment for the node
107
+ std::weak_ptr <ProcessingTimeNode> parent_node_; // !< Weak pointer to the parent node
108
108
std::vector<std::shared_ptr<ProcessingTimeNode>>
109
109
child_nodes_; // !< Vector of shared pointers to the child nodes
110
110
};
Original file line number Diff line number Diff line change @@ -28,7 +28,7 @@ ProcessingTimeNode::ProcessingTimeNode(const std::string & name) : name_(name)
28
28
std::shared_ptr<ProcessingTimeNode> ProcessingTimeNode::add_child (const std::string & name)
29
29
{
30
30
auto new_child_node = std::make_shared<ProcessingTimeNode>(name);
31
- new_child_node->parent_node_ = shared_from_this ();
31
+ new_child_node->parent_node_ = weak_from_this ();
32
32
child_nodes_.push_back (new_child_node);
33
33
return new_child_node;
34
34
}
@@ -86,7 +86,7 @@ tier4_debug_msgs::msg::ProcessingTimeTree ProcessingTimeNode::to_msg() const
86
86
return time_tree_msg;
87
87
}
88
88
89
- std::shared_ptr <ProcessingTimeNode> ProcessingTimeNode::get_parent_node () const
89
+ std::weak_ptr <ProcessingTimeNode> ProcessingTimeNode::get_parent_node () const
90
90
{
91
91
return parent_node_;
92
92
}
@@ -152,7 +152,7 @@ void TimeKeeper::end_track(const std::string & func_name)
152
152
}
153
153
const double processing_time = stop_watch_.toc (func_name);
154
154
current_time_node_->set_time (processing_time);
155
- current_time_node_ = current_time_node_->get_parent_node ();
155
+ current_time_node_ = current_time_node_->get_parent_node (). lock () ;
156
156
157
157
if (current_time_node_ == nullptr ) {
158
158
report ();
You can’t perform that action at this time.
0 commit comments