Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Ros2cli diagnostics #301

Draft
wants to merge 25 commits into
base: ros2
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from 16 commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
28 changes: 28 additions & 0 deletions diagnostics_tutorial/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
# Diagnostics mini tutorial
base on [code from here](http://docs.ros.org/en/melodic/api/diagnostic_updater/html/example_8cpp_source.html)

## DiagnosticTask
[API]()


[code example](diagnostics_tutorial/task_demo.py)

## DiagnosticStatusWrapper
[API](https://docs.ros.org/en/humble/p/diagnostic_updater/generated/classdiagnostic__updater_1_1DiagnosticStatusWrapper.html)
Wrapper for the diagnostic_msgs::msg::DiagnosticStatus message that makes it easier to update and handle

[code example](diagnostics_tutorial/status_wrapper_demo.py)

## CompositeDiagnosticTask
[API](https://docs.ros.org/en/humble/p/diagnostic_updater/generated/classdiagnostic__updater_1_1CompositeDiagnosticTask.html)
The CompositeDiagnosticTask allows multiple DiagnosticTask instances to be combined into a single task that produces a single DiagnosticStatusWrapped

[code example](diagnostics_tutorial/composite_task_demo.py)

## HeaderlessTopicDiagnostic
[API](https://docs.ros.org/en/humble/p/diagnostic_updater/generated/classdiagnostic__updater_1_1HeaderlessTopicDiagnostic.html)
A class to facilitate making diagnostics for a topic using a [FrequencyStatus](#frequencystatus).

## FrequencyStatus
[API](https://docs.ros.org/en/humble/p/diagnostic_updater/generated/classdiagnostic__updater_1_1FrequencyStatus.html#classdiagnostic__updater_1_1FrequencyStatus)
A diagnostic task that monitors the frequency of an event.
Empty file.
53 changes: 53 additions & 0 deletions diagnostics_tutorial/diagnostics_tutorial/composite_task_demo.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,53 @@
import rclpy
from diagnostic_msgs.msg import DiagnosticStatus
from diagnostic_updater import (
CompositeDiagnosticTask,
Updater,
FunctionDiagnosticTask,
DiagnosticStatusWrapper,
)
from rclpy.node import Node


def check_lower_bound(state: DiagnosticStatusWrapper):
state.summary(DiagnosticStatus.OK, "lower ok")
return state


def check_upper_bound(state: DiagnosticStatusWrapper):
state.summary(DiagnosticStatus.OK, "upper ok")
return state


class MyNode(Node):
def __init__(self):
node_name = "minimal"
super().__init__(node_name)
self.diagnostic_updater = Updater(self)
lower = FunctionDiagnosticTask("lower check", check_lower_bound)
upper = FunctionDiagnosticTask("upper check", check_upper_bound)
comp_task = CompositeDiagnosticTask("range demo")
comp_task.addTask(lower)
comp_task.addTask(upper)
self.diagnostic_updater.add(comp_task)
self.create_timer(1.0, self.__timer_handler)
self.get_logger().info("Hello ROS2")

def __timer_handler(self):
self.diagnostic_updater.update()


def main():
rclpy.init()
node = MyNode()
try:
rclpy.spin(node)
except KeyboardInterrupt:
print("User exit")
finally:
node.destroy_node()
rclpy.try_shutdown()


if __name__ == "__main__":
main()
38 changes: 38 additions & 0 deletions diagnostics_tutorial/diagnostics_tutorial/freq_diagnostics_demo.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
import rclpy
from rclpy.node import Node
from diagnostic_updater import HeaderlessTopicDiagnostic, FrequencyStatusParam, Updater


class MyNode(Node):
def __init__(self):
node_name = "frequency_diagnostics"
super().__init__(node_name)

self.diagnostic_updater = Updater(self)
freq_bound = {"min": 0.5, "max": 2}
self.pub_freq = HeaderlessTopicDiagnostic(
"topic1", self.diagnostic_updater, FrequencyStatusParam(freq_bound)
)

self.create_timer(3.0, self.__timer_handler)
self.get_logger().info("Hello ROS2")

def __timer_handler(self):
self.pub_freq.tick()
self.diagnostic_updater.update()


def main(args=None):
rclpy.init(args=args)
node = MyNode()
try:
rclpy.spin(node)
except KeyboardInterrupt:
print("User exit")
finally:
node.destroy_node()
rclpy.try_shutdown()


if __name__ == "__main__":
main()
45 changes: 45 additions & 0 deletions diagnostics_tutorial/diagnostics_tutorial/status_wrapper_demo.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
import rclpy
from diagnostic_msgs.msg import DiagnosticStatus
from diagnostic_updater import DiagnosticStatusWrapper, Updater
from rclpy.node import Node


class DummyClass:
def produce_diagnostics(self, stat: DiagnosticStatusWrapper) -> DiagnosticStatusWrapper:
stat.summary(DiagnosticStatus.WARN, "demo class status")
stat.add("dummy data", "2000")
return stat

def dummy_diagnostics(stat: DiagnosticStatusWrapper) -> DiagnosticStatusWrapper:
stat.summary(DiagnosticStatus.OK, "dummy_diagnostics function")
return stat

class MyNode(Node):
def __init__(self):
node_name = "minimal"
super().__init__(node_name)
self.diagnostic_updater = Updater(self)
dc = DummyClass()
self.diagnostic_updater.add("method updater", dc.produce_diagnostics)
self.diagnostic_updater.add("function update", dummy_diagnostics)
self.create_timer(1.0, self.__timer_handler)
self.get_logger().info("Hello ROS2")

def __timer_handler(self):
self.diagnostic_updater.update()


def main():
rclpy.init()
node = MyNode()
try:
rclpy.spin(node)
except KeyboardInterrupt:
print("User exit")
finally:
node.destroy_node()
rclpy.try_shutdown()


if __name__ == "__main__":
main()
40 changes: 40 additions & 0 deletions diagnostics_tutorial/diagnostics_tutorial/task_demo.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
import rclpy
from rclpy.node import Node
from diagnostic_updater import DiagnosticTask, DiagnosticStatusWrapper, Updater
from diagnostic_msgs.msg import DiagnosticStatus


class DummyTask(DiagnosticTask):
def run(self, stat: DiagnosticStatusWrapper):
stat.summary(DiagnosticStatus.WARN, "DummyTask demo")
return stat


class MyNode(Node):
def __init__(self):
node_name = "minimal"
super().__init__(node_name)
self.diagnostic_updater = Updater(self)
self.diagnostic_updater.setHardwareID("demo hw")
self.diagnostic_updater.add(DummyTask("dummy_task"))
self.create_timer(1.0, self.__timer_handler)
self.get_logger().info("Hello ROS2")

def __timer_handler(self):
self.diagnostic_updater.update()


def main(args=None):
rclpy.init(args=args)
node = MyNode()
try:
rclpy.spin(node)
except KeyboardInterrupt:
print("User exit")
finally:
node.destroy_node()
rclpy.try_shutdown()


if __name__ == "__main__":
main()
18 changes: 18 additions & 0 deletions diagnostics_tutorial/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>diagnostics_tutorial</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="[email protected]">user</maintainer>
<license>TODO: License declaration</license>

<test_depend>ament_copyright</test_depend>
<test_depend>ament_flake8</test_depend>
<test_depend>ament_pep257</test_depend>
<test_depend>python3-pytest</test_depend>

<export>
<build_type>ament_python</build_type>
</export>
</package>
Empty file.
4 changes: 4 additions & 0 deletions diagnostics_tutorial/setup.cfg
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
[develop]
script_dir=$base/lib/diagnostics_tutorial
[install]
install_scripts=$base/lib/diagnostics_tutorial
29 changes: 29 additions & 0 deletions diagnostics_tutorial/setup.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
from setuptools import setup

package_name = "diagnostics_tutorial"

setup(
name=package_name,
version="0.0.0",
packages=[package_name],
data_files=[
("share/ament_index/resource_index/packages", ["resource/" + package_name]),
("share/" + package_name, ["package.xml"]),
],
install_requires=["setuptools"],
zip_safe=True,
maintainer="user",
maintainer_email="[email protected]",
description="TODO: Package description",
license="TODO: License declaration",
tests_require=["pytest"],
entry_points={
"console_scripts": [
"wrapper_demo=diagnostics_tutorial.status_wrapper_demo:main",
"comp=diagnostics_tutorial.composite_task_demo:main",
"freq=diagnostics_tutorial.freq_diagnostics_demo:main",
"task=diagnostics_tutorial.task_demo:main"

],
},
)
25 changes: 25 additions & 0 deletions diagnostics_tutorial/test/test_copyright.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
# Copyright 2015 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

from ament_copyright.main import main
import pytest


# Remove the `skip` decorator once the source file(s) have a copyright header
@pytest.mark.skip(reason='No copyright header has been placed in the generated source file.')
@pytest.mark.copyright
@pytest.mark.linter
def test_copyright():
rc = main(argv=['.', 'test'])
assert rc == 0, 'Found errors'
25 changes: 25 additions & 0 deletions diagnostics_tutorial/test/test_flake8.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
# Copyright 2017 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

from ament_flake8.main import main_with_errors
import pytest


@pytest.mark.flake8
@pytest.mark.linter
def test_flake8():
rc, errors = main_with_errors(argv=[])
assert rc == 0, \
'Found %d code style errors / warnings:\n' % len(errors) + \
'\n'.join(errors)
23 changes: 23 additions & 0 deletions diagnostics_tutorial/test/test_pep257.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
# Copyright 2015 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

from ament_pep257.main import main
import pytest


@pytest.mark.linter
@pytest.mark.pep257
def test_pep257():
rc = main(argv=['.', 'test'])
assert rc == 0, 'Found code style errors / warnings'
Loading