test_digital_output.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 DigitalOutput
00039 
00040 rospy.init_node("test_digital_output")
00041 pub = rospy.Publisher('/mobile_base/commands/digital_output',DigitalOutput)
00042 rate = rospy.Rate(1)
00043 digital_output = DigitalOutput()
00044 digital_output.values = [ False, False, False, False]
00045 digital_output.mask = [ True, True, False, True ]
00046 print ""
00047 print "This program will start sending a variety of digital io signals to the robot."
00048 print "It will set all output signals to false, then iteratively turn each one to True"
00049 print "In doing so, it will cycle through a mask that will negate the setting for one"
00050 print "of the outputs. The process then repeats itself masking the next output in the"
00051 print "sequence instead."
00052 print ""
00053 while not rospy.is_shutdown():
00054     # incrementally convert a false, to true and then reset them all to false.
00055     try:
00056         index = digital_output.values.index(False)
00057         for i in range(0,4):
00058             if not digital_output.values[i]:
00059                 digital_output.values[i] = True
00060                 break
00061     except ValueError:
00062         digital_output.values = [ False, False, False, False]
00063         index = digital_output.mask.index(False)
00064         digital_output.mask[index] = True
00065         if index == 3:
00066             next_index = 0
00067         else:
00068             next_index = index + 1
00069         digital_output.mask[next_index] = False
00070     print digital_output
00071     pub.publish(digital_output)
00072     rate.sleep()
00073     


kobuki_testsuite
Author(s): Jorge Santos Simon
autogenerated on Thu Jun 6 2019 17:38:11