calibrate.py
Go to the documentation of this file.
00001 #!/usr/bin/python
00002 # Software License Agreement (BSD License)
00003 #
00004 # Copyright (c) 2008, 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 the Willow Garage 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 
00035 # Author: Stuart Glaser
00036 
00037 import threading
00038 import sys
00039 from time import sleep
00040 
00041 # Loads interface with the robot.
00042 import rospy
00043 import controller_manager_msgs.srv as controller_manager_srvs
00044 from std_msgs.msg import Bool, Empty
00045 
00046 load_controller = rospy.ServiceProxy('controller_manager/load_controller', controller_manager_srvs.LoadController)
00047 unload_controller = rospy.ServiceProxy('controller_manager/unload_controller', controller_manager_srvs.UnloadController)
00048 switch_controller = rospy.ServiceProxy('controller_manager/switch_controller', controller_manager_srvs.SwitchController)
00049 
00050 def calibrate(controllers):
00051 
00052     success = True
00053 
00054     if type(controllers) is not list:
00055         controllers = [controllers]
00056 
00057     launched = []
00058     try:
00059         # Loads the controllers
00060         for c in controllers:
00061             resp = load_controller(c)
00062             if resp.ok == 0:
00063                 rospy.logerr("Failed: %s" % c)
00064                 success = False
00065             else:
00066                 launched.append(c)
00067         print("Launched: %s" % ', '.join(launched))
00068 
00069         # Starts the launched controllers
00070         switch_controller(launched, [], controller_manager_srvs.SwitchControllerRequest.BEST_EFFORT)
00071 
00072         # Sets up callbacks for calibration completion
00073         waiting_for = launched[:]
00074         def calibrated(msg, name):  # Somewhat not thread-safe
00075             if name in waiting_for:
00076                 waiting_for.remove(name)
00077         for name in waiting_for:
00078             rospy.Subscriber("%s/calibrated" % name, Empty, calibrated, name)
00079 
00080         # Waits until all the controllers have calibrated
00081         while waiting_for and not rospy.is_shutdown():
00082             print("Waiting for: %s" % ', '.join(waiting_for))
00083             sleep(0.5)
00084     finally:
00085         for name in launched:
00086             try:
00087                 resp_stop = switch_controller([], [name], controller_manager_srvs.SwitchControllerRequest.STRICT)
00088                 if (resp_stop == 0):
00089                     rospy.logerr("Failed to stop controller %s" % name)
00090                 resp_unload = unload_controller(name)
00091                 if (resp_unload == 0):
00092                     rospy.logerr("Failed to unload controller %s" % name)
00093             except Exception, ex:
00094                 rospy.logerr("Failed to stop/unload controller %s" % name)
00095     return success
00096 
00097 def calibrate_imu():
00098     class is_calibrated_helper:
00099         def __init__(self):
00100             self.is_calibrated = False
00101             self.cond = threading.Condition()
00102 
00103         def callback(self, msg):
00104             if msg.data:
00105                 with self.cond:
00106                     self.is_calibrated = True
00107                     self.cond.notify()
00108 
00109         def wait_for_calibrated(self, topic, timeout):
00110             self.sub = rospy.Subscriber(topic,Bool,self.callback)
00111             try:
00112                 with self.cond:
00113                     if not self.is_calibrated:
00114                         self.cond.wait(timeout)
00115                 return self.is_calibrated
00116             finally:
00117                 self.sub.unregister()
00118             return self.is_calibrated
00119 
00120     print("Waiting up to 20s for IMU calibration to complete")
00121     helper = is_calibrated_helper()
00122     if not helper.wait_for_calibrated("torso_lift_imu/is_calibrated", 20):
00123         rospy.logerr("IMU took too long to calibrate.")
00124         return False
00125     return True
00126 
00127 def main():
00128     pub_calibrated = rospy.Publisher('calibrated', Bool, queue_size=1, latch=True)
00129     rospy.wait_for_service('controller_manager/load_controller')
00130     rospy.wait_for_service('controller_manager/switch_controller')
00131     rospy.wait_for_service('controller_manager/unload_controller')
00132     if  rospy.is_shutdown():
00133         return
00134 
00135     rospy.init_node('calibration', anonymous=True)
00136     pub_calibrated.publish(False)
00137 
00138     # Don't calibrate the IMU unless ordered to by user
00139     cal_imu = rospy.get_param('calibrate_imu', False)
00140 
00141     if cal_imu:
00142         imustatus = calibrate_imu()
00143     else:
00144         imustatus = True
00145 
00146     controllers = rospy.myargv()[1:]
00147 
00148     if not calibrate(controllers):
00149         sys.exit(3)
00150 
00151     pub_calibrated.publish(True)
00152 
00153     if not imustatus:
00154         print("Mechanism calibration complete, but IMU calibration failed")
00155     else:
00156         print("Calibration complete")
00157 
00158     rospy.spin()
00159 
00160 if __name__ == '__main__':
00161     main()


ros_ethercat_model
Author(s): Manos Nikolaidis
autogenerated on Thu Aug 27 2015 14:47:12