test_events.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # Software License Agreement (BSD License)
00004 #
00005 # Copyright (c) 2012, Yujin Robot
00006 # All rights reserved.
00007 #
00008 # Redistribution and use in source and binary forms, with or without
00009 # modification, are permitted provided that the following conditions
00010 # are met:
00011 #
00012 #  * Redistributions of source code must retain the above copyright
00013 #    notice, this list of conditions and the following disclaimer.
00014 #  * Redistributions in binary form must reproduce the above
00015 #    copyright notice, this list of conditions and the following
00016 #    disclaimer in the documentation and/or other materials provided
00017 #    with the distribution.
00018 #  * Neither the name of the Yujin Robot nor the names of its
00019 #    contributors may be used to endorse or promote products derived
00020 #    from this software without specific prior written permission.
00021 #
00022 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 # POSSIBILITY OF SUCH DAMAGE.
00034 
00035 import roslib; roslib.load_manifest('kobuki_testsuite')
00036 import rospy
00037 
00038 from kobuki_msgs.msg import ButtonEvent
00039 from kobuki_msgs.msg import BumperEvent
00040 from kobuki_msgs.msg import WheelDropEvent
00041 from kobuki_msgs.msg import CliffEvent
00042 from kobuki_msgs.msg import PowerSystemEvent
00043 from kobuki_msgs.msg import DigitalInputEvent
00044 
00045 def ButtonEventCallback(data):
00046     if ( data.state == ButtonEvent.RELEASED ) :
00047         state = "released"
00048     else:
00049         state = "pressed"  
00050     if ( data.button == ButtonEvent.Button0 ) :
00051         button = "B0"
00052     elif ( data.button == ButtonEvent.Button1 ) :
00053         button = "B1"
00054     else:
00055         button = "B2"
00056     rospy.loginfo("Button %s was %s."%(button, state))
00057 
00058 def BumperEventCallback(data):
00059     if ( data.state == BumperEvent.RELEASED ) :
00060         state = "released"
00061     else:
00062         state = "pressed"  
00063     if ( data.bumper == BumperEvent.LEFT ) :
00064         bumper = "Left"
00065     elif ( data.bumper == BumperEvent.CENTER ) :
00066         bumper = "Center"
00067     else:
00068         bumper = "Right"
00069     rospy.loginfo("%s bumper is %s."%(bumper, state))
00070     
00071 def WheelDropEventCallback(data):
00072     if ( data.state == WheelDropEvent.RAISED ) :
00073         state = "raised"
00074     else:
00075         state = "dropped"  
00076     if ( data.wheel == WheelDropEvent.LEFT ) :
00077         wheel = "Left"
00078     else:
00079         wheel = "Right"
00080     rospy.loginfo("%s wheel is %s."%(wheel, state))
00081     
00082 def CliffEventCallback(data):
00083     if ( data.state == CliffEvent.FLOOR ) :
00084         state = "on the floor"
00085     else:
00086         state = "on the cliff"  
00087     if ( data.sensor == CliffEvent.LEFT ) :
00088         cliff = "Left"
00089     elif ( data.sensor == CliffEvent.CENTER ) :
00090         cliff = "Centre"
00091     else:
00092         cliff = "Right"
00093     rospy.loginfo("%s side of robot is %s."%(cliff, state))
00094 
00095 def PowerEventCallback(data):
00096     if   ( data.event == PowerSystemEvent.UNPLUGGED ) :
00097         rospy.loginfo("Robot unplugged")
00098     elif ( data.event == PowerSystemEvent.PLUGGED_TO_ADAPTER ) :
00099         rospy.loginfo("Robot plugged to adapter")
00100     elif ( data.event == PowerSystemEvent.PLUGGED_TO_DOCKBASE ) :
00101         rospy.loginfo("Robot plugged to docking base")
00102     elif ( data.event == PowerSystemEvent.CHARGE_COMPLETED ) :
00103         rospy.loginfo("Robot charge completed")
00104     elif ( data.event == PowerSystemEvent.BATTERY_LOW ) :
00105         rospy.loginfo("Robot battery low")
00106     elif ( data.event == PowerSystemEvent.BATTERY_CRITICAL ) :
00107         rospy.loginfo("Robot battery critical")
00108     else:
00109         rospy.loginfo("WARN: Unexpected power system event: %d"%(data.event))
00110 
00111 def InputEventCallback(data):
00112     val_str = ""
00113     for val in data.values:
00114         val_str = "%s, %s" % (val_str, str(val))
00115     rospy.loginfo("Digital input values: [" + val_str[2:] + "]")
00116     
00117 rospy.init_node("test_events")
00118 rospy.Subscriber("/mobile_base/events/button",ButtonEvent,ButtonEventCallback)
00119 rospy.Subscriber("/mobile_base/events/bumper",BumperEvent,BumperEventCallback)
00120 rospy.Subscriber("/mobile_base/events/wheel_drop",WheelDropEvent,WheelDropEventCallback)
00121 rospy.Subscriber("/mobile_base/events/cliff",CliffEvent,CliffEventCallback)
00122 rospy.Subscriber("/mobile_base/events/power_system",PowerSystemEvent,PowerEventCallback)
00123 rospy.Subscriber("/mobile_base/events/digital_input",DigitalInputEvent,InputEventCallback)
00124 print ""
00125 print "Try kobuki's hardware components; the following events should be reported:"
00126 print "  - buttons"
00127 print "  - bumpers"
00128 print "  - wheel drops"
00129 print "  - cliffs"
00130 print "  - plug/unplug adapter"
00131 print "  - dock/undock on base"
00132 print "  - charge completed"
00133 print "  - battery low/critical"
00134 print "  - digital input changes"
00135 print ""
00136 rospy.spin()
00137     


kobuki_testsuite
Author(s): Jorge Santos Simon
autogenerated on Mon Oct 6 2014 01:33:05