Skip to content

Commit b0708e4

Browse files
ct2034enricosutera
authored andcommitted
Adding uid to log msg (ros-navigation#3750)
* adding uid to the logged message Signed-off-by: Christian Henkel <christian.henkel2@de.bosch.com> * less changes Signed-off-by: Christian Henkel <christian.henkel2@de.bosch.com> --------- Signed-off-by: Christian Henkel <christian.henkel2@de.bosch.com> Signed-off-by: enricosutera <enricosutera@outlook.com>
1 parent 1418e08 commit b0708e4

File tree

2 files changed

+3
-1
lines changed

2 files changed

+3
-1
lines changed

nav2_behavior_tree/include/nav2_behavior_tree/ros_topic_logger.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -69,6 +69,7 @@ class RosTopicLogger : public BT::StatusChangeLogger
6969
// before converting to a msg.
7070
event.timestamp = tf2_ros::toMsg(tf2::TimePoint(timestamp));
7171
event.node_name = node.name();
72+
event.uid = node.UID();
7273
event.previous_status = toStr(prev_status, false);
7374
event.current_status = toStr(status, false);
7475
event_log_.push_back(std::move(event));
Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,5 @@
1-
builtin_interfaces/Time timestamp # internal behavior tree event timestamp. Typically this is wall clock time
1+
builtin_interfaces/Time timestamp # internal behavior tree event timestamp. Typically this is wall clock time
22
string node_name
3+
uint16 uid # unique ID for this node
34
string previous_status # IDLE, RUNNING, SUCCESS or FAILURE
45
string current_status # IDLE, RUNNING, SUCCESS or FAILURE

0 commit comments

Comments
 (0)