Skip to content

Commit

Permalink
fix: method names & verbose logging (#307)
Browse files Browse the repository at this point in the history
  • Loading branch information
KevinSchwarzer authored Jul 27, 2023
1 parent c8941bb commit f67c4b2
Show file tree
Hide file tree
Showing 4 changed files with 56 additions and 4 deletions.
8 changes: 4 additions & 4 deletions diagnostic_updater/diagnostic_updater/_diagnostic_updater.py
Original file line number Diff line number Diff line change
Expand Up @@ -271,13 +271,13 @@ def update(self):

status_vec.append(status)

if status.level:
if status.level != b'\x00':
warn_nohwid = False

if self.verbose and status.level:
if self.verbose and status.level != b'\x00':
self.node.get_logger().warn(
'Non-zero diagnostic status. Name: %s, status\
%i: %s' % (status.name, status.level,
%s: %s' % (status.name, str(status.level),
status.message))

if warn_nohwid and not self.warn_nohwid_done:
Expand All @@ -300,7 +300,7 @@ def period(self):
def period(self, period):
self.__period = period
self.timer.reset()
self.timer = self.node.creat_timer(self.__period, self.udpate)
self.timer = self.node.create_timer(self.__period, self.update)

def force_update(self):
"""Force sending out an update for all known DiagnosticStatus."""
Expand Down
3 changes: 3 additions & 0 deletions diagnostic_updater/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,9 @@
<test_depend>ament_cmake_pytest</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<test_depend>launch</test_depend>
<test_depend>launch_testing</test_depend>
<test_depend>python3-pytest</test_depend>
<test_depend>rclcpp_lifecycle</test_depend>

<export>
Expand Down
23 changes: 23 additions & 0 deletions diagnostic_updater/test/diagnostic_updater_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,8 @@

"""@author Brice Rebsamen <brice [dot] rebsamen [gmail]>."""

import pathlib
import sys
import time
import unittest

Expand All @@ -13,6 +15,10 @@
from diagnostic_updater import FrequencyStatusParam
from diagnostic_updater import TimeStampStatus
from diagnostic_updater import Updater
from launch import LaunchDescription
from launch.actions import ExecuteProcess
from launch_testing.actions import ReadyToTest
import pytest
import rclpy
from rclpy.clock import Clock
from rclpy.clock import ClockType
Expand Down Expand Up @@ -172,6 +178,23 @@ def testTimeStampStatus(self):
'Name should be Timestamp Status')


@pytest.mark.launch_test
def generate_test_description():
return LaunchDescription([
ExecuteProcess(
cmd=[sys.executable, str(pathlib.Path(__file__).parent / 'dummy_process.py')],
name='test_node',
),
ReadyToTest()
])


class TestProcessOutput(unittest.TestCase):

def testProcessOutput(self, proc_output):
proc_output.assertWaitFor('Non-zero diagnostic status.', timeout=1.0, stream='stderr')


if __name__ == '__main__':
rclpy.init()
unittest.main()
26 changes: 26 additions & 0 deletions diagnostic_updater/test/dummy_process.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
#!/usr/bin/env python3

from diagnostic_updater import Updater
import rclpy


def main():
rclpy.init()

node = rclpy.create_node('talker')
updater = Updater(node)
updater.add('do_nothing', lambda stat: stat)
updater.verbose = True
node.create_timer(0.1, lambda: updater.update())

try:
rclpy.spin(node)
except KeyboardInterrupt:
pass
finally:
node.destroy_node()
rclpy.try_shutdown()


if __name__ == '__main__':
main()

0 comments on commit f67c4b2

Please sign in to comment.