fake_driver.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00004 #
00005 # Licensed under the Apache License, Version 2.0 (the "License");
00006 # you may not use this file except in compliance with the License.
00007 # You may obtain a copy of the License at
00008 #
00009 #   http://www.apache.org/licenses/LICENSE-2.0
00010 #
00011 # Unless required by applicable law or agreed to in writing, software
00012 # distributed under the License is distributed on an "AS IS" BASIS,
00013 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00014 # See the License for the specific language governing permissions and
00015 # limitations under the License.
00016 
00017 
00018 import rospy
00019 from std_srvs.srv import *
00020 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus
00021 
00022 class FakeDriver():
00023 
00024     def __init__(self):
00025         self.init_srv = rospy.Service('driver/init', Trigger, self.srv_cb)
00026         self.recover_srv = rospy.Service('driver/recover', Trigger, self.srv_cb)
00027         self.halt_srv = rospy.Service('driver/halt', Trigger, self.srv_cb)
00028         self.shutdown_srv = rospy.Service('driver/shutdown', Trigger, self.srv_cb)
00029 
00030         self._fake_diag_pub = rospy.Publisher('/diagnostics', DiagnosticArray, queue_size=1)
00031         rospy.Timer(rospy.Duration(1.0), self.publish_diagnostics)
00032 
00033     def publish_diagnostics(self, event):
00034         msg = DiagnosticArray()
00035         msg.header.stamp = rospy.get_rostime()
00036 
00037         status = DiagnosticStatus()
00038         status.name = rospy.get_name()
00039         status.level = DiagnosticStatus.OK
00040         status.message = "fake diagnostics"
00041         status.hardware_id = rospy.get_name()
00042         msg.status.append(status)
00043 
00044         self._fake_diag_pub.publish(msg)
00045 
00046     def srv_cb(self, req):
00047         resp = TriggerResponse()
00048         resp.success = True
00049         return resp
00050 
00051 
00052 if __name__ == "__main__":
00053    rospy.init_node('fake_driver')
00054    FakeDriver()
00055    rospy.loginfo("fake_driver running")
00056    rospy.spin()
00057 


cob_helper_tools
Author(s): Felix Messmer
autogenerated on Sun Jun 9 2019 20:20:17