|
42 | 42 |
|
43 | 43 | from rclpy.expand_topic_name import expand_topic_name |
44 | 44 | from rclpy.qos import qos_profile_sensor_data |
| 45 | +from rclpy.time import Time |
45 | 46 | from rclpy.validate_full_topic_name import validate_full_topic_name |
46 | 47 | from ros2cli.node.direct import DirectNode |
47 | 48 | from ros2topic.api import get_topic_names_and_types |
@@ -114,12 +115,9 @@ def callback_delay(self, msg): |
114 | 115 | self.msg_tn = curr |
115 | 116 | self.delays = [] |
116 | 117 | else: |
117 | | - curr_sec = curr_rostime.to_msg().sec |
118 | | - curr_nanosec = curr_rostime.to_msg().nanosec |
119 | | - |
120 | | - delay = ((curr_sec + curr_nanosec * 1e-9) - |
121 | | - (msg.header.stamp.sec + msg.header.stamp.nanosec * 1e-9)) |
122 | | - self.delays.append(delay) |
| 118 | + # store the duration nanoseconds in self.delays |
| 119 | + duration = (curr_rostime - Time.from_msg(msg.header.stamp)) |
| 120 | + self.delays.append(duration.nanoseconds) |
123 | 121 | self.msg_tn = curr |
124 | 122 |
|
125 | 123 | if len(self.delays) > self.window_size: |
@@ -158,8 +156,9 @@ def print_delay(self): |
158 | 156 | print('no new messages') |
159 | 157 | return |
160 | 158 | delay, min_delta, max_delta, std_dev, window = ret |
| 159 | + # convert nanoseconds to seconds when print |
161 | 160 | print('average delay: %.3f\n\tmin: %.3fs max: %.3fs std dev: %.5fs window: %s' |
162 | | - % (delay, min_delta, max_delta, std_dev, window)) |
| 161 | + % (delay * 1e-9, min_delta * 1e-9, max_delta * 1e-9, std_dev * 1e-9, window)) |
163 | 162 |
|
164 | 163 |
|
165 | 164 | def _rostopic_delay(node, topic, window_size=-1): |
|
0 commit comments