analog_io_rampup.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # Copyright (c) 2013-2015, Rethink Robotics
00004 # All rights reserved.
00005 #
00006 # Redistribution and use in source and binary forms, with or without
00007 # modification, are permitted provided that the following conditions are met:
00008 #
00009 # 1. Redistributions of source code must retain the above copyright notice,
00010 #    this list of conditions and the following disclaimer.
00011 # 2. Redistributions in binary form must reproduce the above copyright
00012 #    notice, this list of conditions and the following disclaimer in the
00013 #    documentation and/or other materials provided with the distribution.
00014 # 3. Neither the name of the Rethink Robotics nor the names of its
00015 #    contributors may be used to endorse or promote products derived from
00016 #    this software without specific prior written permission.
00017 #
00018 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00019 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00020 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00021 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00022 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00023 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00024 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00025 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00026 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00027 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00028 # POSSIBILITY OF SUCH DAMAGE.
00029 
00030 import argparse
00031 
00032 import rospy
00033 
00034 import baxter_interface.analog_io as AIO
00035 
00036 
00037 def test_interface(io_component='torso_fan'):
00038     """Ramps an Analog component from 0 to 100, then back down to 0."""
00039     rospy.loginfo("Ramping output of Analog IO component: %s", io_component)
00040 
00041     b = AIO.AnalogIO(io_component)
00042     rate = rospy.Rate(2)
00043 
00044     # start: 0.0
00045     print b.state()
00046 
00047     # ramp up
00048     for i in range(0, 101, 10):
00049         b.set_output(i)
00050         print i
00051         rate.sleep()
00052     # max: 100.0
00053     print b.state()
00054 
00055     # ramp down
00056     for i in range(100, -1, -10):
00057         b.set_output(i)
00058         print i
00059         rate.sleep()
00060     # (fans off)
00061     b.set_output(0)
00062 
00063 
00064 def main():
00065     """RSDK Analog IO Example: Ramp
00066 
00067     Ramps the output of an AnalogIO component from 0 to 100,
00068     and then back down again. Demonstrates the use of the
00069     baxter_interface.AnalogIO class.
00070 
00071     Run this example and listen to the fan as output changes.
00072     """
00073     epilog = """
00074 ROS Parameters:
00075   ~component_id        - name of AnalogIO component to use
00076 
00077 Baxter AnalogIO
00078     Note that 'AnalogIO' components are only those that use
00079     the custom ROS Messages baxter_core_msgs/AnalogIOState
00080     and baxter_core_msgs/AnalogOutputCommand.
00081 
00082     AnalogIO component names can be found on the Wiki or by
00083     echoing the names field of the analog_io_states topic:
00084       $ rostopic echo -n 1 /robot/analog_io_states/names
00085     """
00086     arg_fmt = argparse.RawDescriptionHelpFormatter
00087     parser = argparse.ArgumentParser(formatter_class=arg_fmt,
00088                                      description=main.__doc__,
00089                                      epilog=epilog)
00090     parser.add_argument(
00091         '-c', '--component', dest='component_id', default='torso_fan',
00092         help='name of Analog IO component to use (default:= torso_fan)'
00093     )
00094     args = parser.parse_args(rospy.myargv()[1:])
00095 
00096     rospy.init_node('rsdk_analog_io_rampup', anonymous=True)
00097     io_component = rospy.get_param('~component_id', args.component_id)
00098     test_interface(io_component)
00099 
00100 if __name__ == '__main__':
00101     main()


baxter_examples
Author(s): Rethink Robotics Inc.
autogenerated on Thu Aug 27 2015 12:31:14