update_robot.py
Go to the documentation of this file.
00001 #!/usr/bin/python2
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 errno
00031 import argparse
00032 import os
00033 import sys
00034 import re
00035 
00036 import rospy
00037 
00038 import std_msgs.msg
00039 
00040 import baxter_dataflow
00041 
00042 from baxter_maintenance_msgs.msg import (
00043     UpdateSources,
00044     UpdateStatus,
00045 )
00046 
00047 
00048 class Updater(object):
00049     """
00050     Control the updater on the robot.
00051 
00052     Signals:
00053         status_changed:     Fired when the update status changes.  Passes
00054                             the current UpdateStatus message.
00055     """
00056     def __init__(self):
00057         self.status_changed = baxter_dataflow.Signal()
00058 
00059         self._status = UpdateStatus()
00060         self._avail_updates = UpdateSources()
00061 
00062         self._update_sources = rospy.Subscriber(
00063             '/usb/update_sources',
00064             UpdateSources,
00065             self._on_update_sources)
00066 
00067         self._updater_status_sub = rospy.Subscriber(
00068             '/updater/status',
00069             UpdateStatus,
00070             self._on_update_status)
00071 
00072         self._updater_start = rospy.Publisher(
00073             '/updater/start',
00074             std_msgs.msg.String,
00075             queue_size=10)
00076 
00077         self._updater_stop = rospy.Publisher(
00078             '/updater/stop',
00079             std_msgs.msg.Empty,
00080             queue_size=10)
00081 
00082         baxter_dataflow.wait_for(
00083             lambda: self._avail_updates.uuid != '',
00084             timeout=5.0,
00085             timeout_msg="Failed to get list of available updates"
00086         )
00087 
00088     def _on_update_sources(self, msg):
00089         if msg.uuid != self._avail_updates.uuid:
00090             self._avail_updates = msg
00091 
00092     def _on_update_status(self, msg):
00093         if self._status != msg:
00094             self._status = msg
00095             self.status_changed(msg)
00096 
00097     def list(self):
00098         """
00099         Return a list of tuples (version, uuid) of all available updates
00100         """
00101         return [(u.version, u.uuid) for u in self._avail_updates.sources]
00102 
00103     def command_update(self, uuid):
00104         """
00105         Command the robot to launch the update with the given uuid.
00106 
00107         @param uuid: uuid of the update to start.
00108         """
00109         if not any([u.uuid == uuid for u in self._avail_updates.sources]):
00110             raise OSError(errno.EINVAL, "Invalid update uuid '%s'" % (uuid,))
00111 
00112         self._updater_start.publish(std_msgs.msg.String(uuid))
00113 
00114     def stop_update(self):
00115         """
00116         Stop the current update process, if any.
00117         """
00118         self._updater_stop.publish()
00119 
00120 
00121 def run_update(updater, uuid):
00122     """
00123     Run and monitor the progress of an update.
00124 
00125     @param updater: Instance of Updater to use.
00126     @param uuid: update uuid.
00127     """
00128 
00129     # Work around lack of a nonlocal keyword in python 2.x
00130     class NonLocal(object):
00131         pass
00132 
00133     nl = NonLocal
00134     nl.rc = 1
00135     nl.done = False
00136 
00137     def on_update_status(msg):
00138         if msg.status == UpdateStatus.STS_IDLE:
00139             nl.done = True
00140         elif msg.status == UpdateStatus.STS_INVALID:
00141             print ("Invalid update uuid, '%s'." % (uuid,))
00142             nl.done = True
00143         elif msg.status == UpdateStatus.STS_BUSY:
00144             print ("Update already in progress (may be shutting down).")
00145             nl.done = True
00146         elif msg.status == UpdateStatus.STS_CANCELLED:
00147             print ("Update cancelled.")
00148             nl.done = True
00149         elif msg.status == UpdateStatus.STS_ERR:
00150             print ("Update failed: %s." % (msg.long_description,))
00151             nl.done = True
00152             nl.rc = 1
00153         elif msg.status == UpdateStatus.STS_LOAD_KEXEC:
00154             print ("Robot will now reboot to finish updating...")
00155             nl.rc = 0
00156         else:
00157             print ("Updater:  %s" % (msg.long_description))
00158 
00159     def on_shutdown():
00160         updater.stop_update()
00161     rospy.on_shutdown(on_shutdown)
00162 
00163     updater.status_changed.connect(on_update_status)
00164 
00165     try:
00166         updater.command_update(uuid)
00167     except OSError, e:
00168         if e.errno == errno.EINVAL:
00169             print e.strerror
00170             return 1
00171         raise
00172 
00173     try:
00174         baxter_dataflow.wait_for(
00175             lambda: nl.done == True,
00176             timeout=5 * 60,
00177             timeout_msg="Timeout waiting for update to succeed"
00178         )
00179     except Exception, e:
00180         if not (hasattr(e, 'errno') and e.errno == errno.ESHUTDOWN):
00181             print e.strerror
00182         nl.rc = 1
00183 
00184     return nl.rc
00185 
00186 
00187 def ros_updateable_version():
00188     """
00189     Verifies the version of the software is older than 1.1.0.
00190     If newer, print out url to SSH update instructions
00191     and return False
00192     """
00193     ros_updateable = True
00194 
00195     def get_robot_version():
00196         param_name = "rethink/software_version"
00197         robot_version = rospy.get_param(param_name, None)
00198         # parse out first 3 digits of robot version tag
00199         pattern = ("^([0-9]+)\.([0-9]+)\.([0-9]+)")
00200         match = re.search(pattern, robot_version)
00201         if not match:
00202             rospy.logwarn("RobotUpdater: Invalid robot version: %s",
00203                           robot_version)
00204             return None
00205         return match.string[match.start(1):match.end(3)]
00206 
00207     robot_version = get_robot_version()
00208     if not robot_version:
00209         rospy.logerr("RobotUpdater: Failed to retrieve robot version "
00210                      "from rosparam: %s\n"
00211                      "Verify robot state and connectivity "
00212                      "(i.e. ROS_MASTER_URI)", param_name)
00213         ros_updateable = False
00214     else:
00215         v_list = robot_version.split('.')
00216         # If Version >= 1.1, SSH required
00217         if ((float(v_list[0]) > 1) or
00218            (float(v_list[0]) == 1 and float(v_list[1]) >= 1)):
00219             errstr_version = ("RobotUpdater: Your Baxter's software "
00220                               "version is (%s).\nFor robots with software "
00221                               "1.1.0 and newer, software updates must be run "
00222                               "by SSH'ing into the robot\n"
00223                               "or by switching to Baxter's Display TTY1 with "
00224                               "a keyboard. Be sure to insert a USB flash "
00225                               "drive\ncontaining the update. "
00226                               "After logging into the robot, run:\n"
00227                               "  ruser@baxter ~ $ rethink-updater --list\n"
00228                               "  Version\n"
00229                               "  some.version.num.ber\n"
00230                               "  ruser@baxter ~ $ rethink-updater --update "
00231                               "some.version.num.ber\n"
00232                               "Please see "
00233                               "http://sdk.rethinkrobotics.com/wiki/SSH_Update "
00234                               "for a detailed tutorial on updating.")
00235             rospy.logerr(errstr_version, robot_version)
00236             ros_updateable = False
00237     return ros_updateable
00238 
00239 
00240 def main():
00241     description = "Legacy Robot Updater Script for versions 1.0.0 and earlier."
00242     parser = argparse.ArgumentParser(description=description)
00243     required = parser.add_mutually_exclusive_group()
00244     required.add_argument('-l', '--list', action='store_const',
00245                           dest='cmd', const='list', default='update',
00246                           help="List available updates and UUID's")
00247     required.add_argument('-u', '--update', dest='uuid', default='',
00248                           help='Launch the given update')
00249     args = parser.parse_args(rospy.myargv()[1:])
00250     cmd = args.cmd
00251     uuid = args.uuid
00252 
00253     rospy.init_node('rsdk_update_robot')
00254     if not ros_updateable_version():
00255         sys.exit(1)
00256     updater = Updater()
00257 
00258     if cmd == 'list':
00259         updates = updater.list()
00260         if not len(updates):
00261             print ("No available updates")
00262         else:
00263             print ("%-30s%s" % ("Version", "UUID"))
00264             for update in updates:
00265                 print("%-30s%s" % (update[0], update[1]))
00266         return 0
00267     elif cmd == 'update':
00268         if uuid == '':
00269             print "Error:  no update uuid specified"
00270             return 1
00271         msg = ("NOTE: Please plug in any Rethink Electric Parallel Grippers\n"
00272                "      into the robot now, so that the Gripper Firmware\n"
00273                "      can be automatically upgraded with the robot.\n")
00274         print (msg)
00275         raw_input("Press <Enter> to Continue...")
00276         if rospy.is_shutdown():
00277             return 0
00278         return run_update(updater, uuid)
00279 
00280 if __name__ == '__main__':
00281     sys.exit(main())


baxter_tools
Author(s): Rethink Robotics Inc.
autogenerated on Wed Aug 26 2015 10:50:53