[ros-users] Help with ROS Diagnostics
Felipe Roman
roman.felipe at gmail.com
Thu Jun 26 15:47:32 UTC 2014
Hi Guillaume,
Thank you very much for the example. I will have a look on that. Actually I
already developed a C++ plugin but now I am trying to figure out how to
simulate the robot side (create and publish information on a diagnostic
topic) for test integration with Nagios.
Let me know if my source code could be useful and I can send here too.
Regards,
Roman
On Wed, Jun 25, 2014 at 10:06 AM, Guillaume Schreiner <schreiner at unistra.fr>
wrote:
> Hello,
>
> here’s an example of Nagios plugin written in Python interacting with ROS
> framework.
>
> #!/usr/bin/env python
>
> import sys
>
> sys.path.append("/home/schreiner/catkin_ws_hydro/install/lib/python2.7/dist-packages")
> sys.path.append("/opt/ros/hydro/lib/python2.7/dist-packages")
>
> import os
> os.environ['PATH'] = "/opt/ros/hydro/bin:" + os.environ['PATH']
> os.environ['ROS_PACKAGE_PATH']=
> '/home/schreiner/catkin_ws_hydro/install/share:/home/schreiner/catkin_ws_hydro/install/stacks:/opt/ros/hydro/share:/opt/ros/hydro/stacks'
>
> from optparse import OptionParser
>
> import rospy
> import rosnode
> import os
> import roslib
> import sys
> roslib.load_manifest('linux_hardware')
> from linux_hardware.msg import LaptopChargeStatus
> from diagnostic_msgs.msg import DiagnosticStatus, DiagnosticArray, KeyValue
>
> # Exit statuses recognized by Nagios
> UNKNOWN = -1
> OK = 0
> WARNING = 1
> CRITICAL = 2
>
> # TEMPLATE FOR READING PARAMETERS FROM COMMANDLINE
> parser = OptionParser()
> parser.add_option("-H", "--host", dest="host", default='localhost',
> help="A message to print after OK - ")
> parser.add_option("-w", "--warning", dest="warning", default='40', help="A
> message to print after OK - ")
> parser.add_option("-c", "--critical", dest="critical", default='20',
> help="A message to print after OK - ")
> (options, args) = parser.parse_args()
>
> # Set turtlebot ROS Master URI
> os.environ['ROS_MASTER_URI'] = 'http://' + options.host + ':11311'
>
> kobuki_charge = None
> kobuki_percentage = None
>
> def callback_kobuki(data):
> global kobuki_charge
> global kobuki_percentage
>
> ready = False
>
> while not ready:
> for current in data.status:
> if current.name == "mobile_base_nodelet_manager: Battery":
> for value in current.values:
> if value.key == "Charge (Ah)":
> kobuki_charge = value.value
> if value.key == "Percent":
> kobuki_percentage = value.value
> ready = True
>
> time = rospy.get_time()
> kobuki_percentage = int(float(kobuki_percentage))
> rospy.signal_shutdown(0)
>
> def listener():
> rospy.init_node('check_battery_kobuki', anonymous=True,
> disable_signals=True)
> rospy.Subscriber("diagnostics", DiagnosticArray , callback_kobuki)
> rospy.spin()
>
> def myhook():
> if kobuki_percentage < int(options.critical):
> print "CRITICAL - Kobuki Charge Percent %s | kobuki_battery=%s" %
> (kobuki_percentage,kobuki_percentage)
> exiting(CRITICAL)
> elif kobuki_percentage < int(options.warning):
> print "WARNING - Kobuki Charge Percent %s | kobuki_battery=%s" %
> (kobuki_percentage,kobuki_percentage)
> exiting(WARNING)
> else:
> print "OK - Kobuki Charge Percent %s | kobuki_battery=%s" %
> (kobuki_percentage,kobuki_percentage)
> exiting(OK)
>
> def exiting(value):
> try:
> sys.stdout.flush()
> os._exit(value)
> except:
> pass
>
> if __name__ == '__main__':
> try:
> master = rospy.get_master()
> master.getPid()
> except Exception:
> print "UNKNOWN - Roscore not available"
> exiting(UNKNOWN)
>
> try:
> if len(sys.argv) < 5:
> print "usage %s -c <critical> -w <warning>" % (sys.argv[0])
> exiting(UNKNOWN)
> rospy.on_shutdown(myhook)
> listener()
> except rospy.ROSInterruptException:
> exit
>
> --
> Guillaume Schreiner
> Research Engineer
> Network Research Group
> ICube - UMR CNRS 7357
> Strasbourg University
>
>
> Le 25 juin 2014 à 13:47, Dominik Kirchner <kirchner at vs.uni-kassel.de> a
> écrit :
>
> Hi,
>
> the Nagios plugin needs to pubish its monitoring data on the /diagnostic
> topic. Msg type needs to be a DiagnosticArray with DiagnosticStatus items
> for each entity you have monitored.
>
> You will find good tutorials on how use the ROS diagnostic stack on
> http://wiki.ros.org/diagnostics/Tutorials.
>
> Best Regards,
> Dominik Kirchner
>
>
> On 24.06.2014 22:40, Felipe Roman wrote:
>
> Hi Everyone,
>
> Has anyone have used ROS diagnostics before ? I am working on a research
> work to integrate ROS with one IT monitoring tool (Nagios). Basically this
> IT monitoring tool will be able to get information about the Robot Sensor
> Status.
>
> I already have implemented the communication between them (Nagios plugin
> reading ROS service information) and now I would like to know how to create
> and configure a ROS diagnostic topic to test it.
>
> Any ideas will be welcome, thanks in advance
>
> --
> Best Regards,
> Felipe Roman
> Phone 55 51 8454 8110
> LinkedIn http://au.linkedin.com/in/feliperoman
>
>
> _______________________________________________
> ros-users mailing listros-users at lists.ros.orghttp://lists.ros.org/mailman/listinfo/ros-users
>
>
> --
> --
> -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- --
> -- Dominik Kirchner - kirchner at vs.uni-kassel.de - T. +49 561 804-6279
> -- Univ. Kassel - FB 16, Wilhelmshöher Allee 73, D-34121 Kassel
> -- http://www.uni-kassel.de/eecs/fachgebiete/vs/team/person/677-Dominik-Kirchner.html
> ------------------------------------------------------------------------
>
> _______________________________________________
> ros-users mailing list
> ros-users at lists.ros.org
> http://lists.ros.org/mailman/listinfo/ros-users
>
>
>
> _______________________________________________
> ros-users mailing list
> ros-users at lists.ros.org
> http://lists.ros.org/mailman/listinfo/ros-users
>
>
--
Best Regards,
Felipe Roman
Phone 55 51 8454 8110
LinkedIn http://au.linkedin.com/in/feliperoman
-------------- next part --------------
An HTML attachment was scrubbed...
URL: <http://lists.ros.org/pipermail/ros-users/attachments/20140626/a3bbab85/attachment.html>
More information about the ros-users
mailing list