setup_xbee.py
Go to the documentation of this file.
00001 #! /usr/bin/env python
00002 # Software License Agreement (BSD License)
00003 #
00004 # Copyright (c) 2011, Willow Garage, Inc.
00005 # All rights reserved.
00006 #
00007 # Redistribution and use in source and binary forms, with or without
00008 # modification, are permitted provided that the following conditions
00009 # are met:
00010 #
00011 #  * Redistributions of source code must retain the above copyright
00012 #    notice, this list of conditions and the following disclaimer.
00013 #  * Redistributions in binary form must reproduce the above
00014 #    copyright notice, this list of conditions and the following
00015 #    disclaimer in the documentation and/or other materials provided
00016 #    with the distribution.
00017 #  * Neither the name of Willow Garage, Inc. nor the names of its
00018 #    contributors may be used to endorse or promote products derived
00019 #    from this software without specific prior written permission.
00020 #
00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 # POSSIBILITY OF SUCH DAMAGE.
00033 
00034 __author__ = "astambler@willowgarage.com (Adam Stambler)"
00035 
00036 
00037 import serial
00038 import yaml
00039 import sys
00040 import time 
00041 
00042 from optparse import OptionParser
00043 
00044 #               
00045 
00046 help = """
00047 %prog [options] port my_adr
00048 
00049 setup_xbee.py is a configuration script for Xbees.  It takes  
00050 factory fresh xbee and programs it to work with your rosserial network.
00051 If XBee is not factory fresh, use Digi's X-CTU software to program it.
00052 
00053     port :    serial port of port of the xbee (/dev/ttyUSB0)
00054     my_adr:   MY address is the 16 bit address of this xbee in the 
00055               network. This must be a unique address in the network.
00056               This address is always 0 for the coordinator.  """
00057 parser = OptionParser(usage=help)
00058 
00059 
00060 parser.add_option('-P', '--pan_id', action="store", type="int", dest="pan_id", default=1331, help="Pan ID of the xbee network.  This ID must be the same for all XBees in your network.")
00061 parser.add_option('-c', '--channel', action="store", type="string", dest="channel", default="0D", help="Frequency channel for the xbee network. The channel value must be the same for all XBees in your network.")
00062 parser.add_option('-C', '--coordinator', action="store_true", dest="coordinator", default=False, help="Configures the XBee as Coordinator for the network.  Only make the XBee connected to the computer a coordiantor.")
00063 
00064 
00065 
00066 def send(port, cmd):
00067         for c in cmd+'\r':
00068                 port.write(c)
00069                 time.sleep(0.06)
00070                 
00071 def setAT(port, cmd):
00072         port.flushInput()
00073         send(port, 'AT'+cmd)
00074         rsp = port.readline()
00075         print rsp
00076         if 'OK' in rsp:
00077                 return True
00078         else :
00079                 return False
00080 
00081 baud_lookup= { 1200   : 0, 
00082                            2400   : 1,
00083                            4800   : 2,
00084                            9600   : 3,
00085                            19200  : 4,
00086                            38400  : 5,
00087                            57600  : 6,
00088                            115200 : 7}
00089 
00090 
00091         
00092 def beginAtMode(port):
00093         
00094         for i in range(0,3):
00095                 port.write('+')
00096                 time.sleep(0.05)
00097         time.sleep(1)
00098         if port.read(2) == 'OK':
00099                 return True
00100         else :
00101                 return False
00102 
00103 if __name__ == '__main__':
00104         
00105         opts, args = parser.parse_args()
00106         
00107         if len(args) < 2:
00108                 print "Not enough arguments!"
00109                 exit()
00110         
00111         baud = 9600
00112         port_name = args[0]
00113         my_address = int(args[1])
00114 
00115         port = serial.Serial(port_name, baud, timeout=1.5)
00116         
00117         if beginAtMode(port):
00118                 print "Connected to the XBee"
00119         else:
00120                 print "Failed to connect to the XBee"
00121                 exit()
00122 
00123         
00124         cmd = ''
00125         if (opts.coordinator):
00126                 cmd += 'AP2,CE1,' #API mode 2, and enable coordinator
00127         
00128         cmd += 'MY%d,'%int(args[1]) #set the xbee address
00129         cmd += 'BD%d,'%baud_lookup[57600] #set the xbee to interface at 57600 baud
00130         cmd += 'ID%d,'%opts.pan_id
00131         cmd += 'CH%s,'%opts.channel
00132         cmd += 'DL0,'
00133         cmd += 'RN1,' #enables collision avoidance on first transmission
00134         cmd += 'RO5,' #sets packetization timeout to 5 characters
00135         cmd += 'WR' #wrtie the commands to nonvolatile memory
00136 
00137                 
00138         if setAT(port, 'RE'): #reset the xbee
00139                 print "XBee reset"
00140         else:
00141                 print "Reset failed"
00142                 exit()
00143         beginAtMode(port)
00144         time.sleep(1)
00145         print "Sending command : ", cmd
00146 
00147         if setAT(port, cmd):
00148                 print "XBee sucessfully programed!"
00149         else:
00150                 print "XBee programming failed.  Try again and then investigate using X-CTU"
00151 
00152         
00153                 


rosserial_xbee
Author(s): Adam Stambler
autogenerated on Fri Dec 6 2013 20:35:48