nextage_client.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # Software License Agreement (BSD License)
00004 #
00005 # Copyright (c) 2013, Tokyo Opensource Robotics Kyokai Association
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 Tokyo Opensource Robotics Kyokai Association. nor the
00019 #    names of its contributors may be used to endorse or promote products
00020 #    derived 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 # Author: Isaac Isao Saito
00036 
00037 from hironx_ros_bridge.hironx_client import HIRONX
00038 
00039 from nextage_ros_bridge.iros13_hands import Iros13Hands
00040 
00041 
00042 class NextageClient(HIRONX, object):
00043     # The 2nd arg 'object' is passed to work around the issue raised because
00044     # HrpsysConfigurator is "old-style" python class.
00045     # See http://stackoverflow.com/a/18392639/577001
00046     '''
00047     This class holds methods that are specific to Kawada Industries' dual-arm
00048     robot called Nextage Open.
00049     '''
00050     # TODO: Unittest s'il vous plait!
00051 
00052     ''' Overriding a variable in the superclass to set the arms at higher
00053     positions.'''
00054     OffPose = [[0], [0, 0],
00055                [25, -140, -150, 45, 0, 0],
00056                [-25, -140, -150, -45, 0, 0],
00057                [0, 0, 0, 0],
00058                [0, 0, 0, 0]]
00059     InitialPose = [[0], [0, 0],
00060                    [-0, 0, -130, 0, 0, 0],
00061                    [0, 0, -130, 0, 0, 0],
00062                    [0, 0, 0, 0],
00063                    [0, 0, 0, 0]]
00064 
00065     def __init__(self):
00066         '''
00067         Do not get confused that there is also a method called
00068         'init' (without trailing underscores) that is succeeded from the
00069         super class as the tradition there.
00070         '''
00071         super(NextageClient, self).__init__()
00072         self._hand = Iros13Hands(self)
00073 
00074     def init(self, robotname="HiroNX(Robot)0", url=""):
00075         '''
00076         Calls init from its superclass, which tries to connect RTCManager,
00077         looks for ModelLoader, and starts necessary RTC components. Also runs
00078         config, logger.
00079         Also internally calls setSelfGroups().
00080 
00081         @type robotname: str
00082         @type url: str
00083         '''
00084         HIRONX.init(self, robotname=robotname, url=url)
00085 
00086     def turn_handlight_r(self, is_on=True):
00087         self._hand.turn_handlight(self._hand.HAND_R, is_on)
00088 
00089     def turn_handlight_l(self, is_on=True):
00090         self._hand.turn_handlight(self._hand.HAND_L, is_on)
00091 
00092     def turn_handlight_both(self, is_on=True):
00093         self._hand.turn_handlight(None, is_on)
00094 
00095     def handtool_eject_l(self):
00096         self._hand.toolchanger_l_command.execute(
00097             self._hand.toolchanger_l_command.HAND_TOOLCHANGE_OFF)
00098 
00099     def handtool_eject_r(self):
00100         self._hand.toolchanger_r_command.execute(
00101             self._hand.toolchanger_r_command.HAND_TOOLCHANGE_OFF)
00102 
00103     def handtool_attach_l(self):
00104         self._hand.toolchanger_l_command.execute(
00105             self._hand.toolchanger_l_command.HAND_TOOLCHANGE_ON)
00106 
00107     def handtool_attach_r(self):
00108         self._hand.toolchanger_r_command.execute(
00109             self._hand.toolchanger_r_command.HAND_TOOLCHANGE_ON)
00110 
00111     def gripper_close_l(self):
00112         self._hand.gripper_l_command.execute(
00113             self._hand.gripper_l_command.GRIPPER_CLOSE)
00114 
00115     def gripper_close_r(self):
00116         self._hand.gripper_r_command.execute(
00117             self._hand.gripper_r_command.GRIPPER_CLOSE)
00118 
00119     def gripper_open_l(self):
00120         self._hand.gripper_l_command.execute(
00121             self._hand.gripper_r_command.GRIPPER_OPEN)
00122 
00123     def gripper_open_r(self):
00124         self._hand.gripper_r_command.execute(
00125             self._hand.gripper_r_command.GRIPPER_OPEN)
00126 
00127     def airhand_drawin_l(self):
00128         self._hand.airhand_l_command.execute(
00129             self._hand.airhand_l_command.AIRHAND_DRAWIN)
00130 
00131     def airhand_drawin_r(self):
00132         self._hand.airhand_r_command.execute(
00133             self._hand.airhand_r_command.AIRHAND_DRAWIN)
00134 
00135     def airhand_keep_l(self):
00136         self._hand.airhand_l_command.execute(
00137             self._hand.airhand_l_command.AIRHAND_KEEP)
00138 
00139     def airhand_keep_r(self):
00140         self._hand.airhand_r_command.execute(
00141             self._hand.airhand_r_command.AIRHAND_KEEP)
00142 
00143     def airhand_release_l(self):
00144         self._hand.airhand_l_command.execute(
00145             self._hand.airhand_l_command.AIRHAND_RELEASE)
00146 
00147     def airhand_release_r(self):
00148         self._hand.airhand_r_command.execute(
00149             self._hand.airhand_r_command.AIRHAND_RELEASE)
00150 
00151     def initialize_hand_dio(self):
00152         '''
00153         Reset all DIO channels to "off" state except for toolchanger lockers
00154         (if they are turned off the attached tools will fall).
00155         '''
00156         self._hand.init_dio()
00157 
00158     # 1/15/2014 130s debug
00159     def getRTCList(self):
00160         '''
00161         Overwriting HrpsysConfigurator.getRTCList
00162         Returning predefined list of RT components.
00163         @rtype [[str]]
00164         @rerutrn List of available components. Each element consists of a list
00165                  of abbreviated and full names of the component.
00166         '''
00167         return [
00168             ['seq', "SequencePlayer"],
00169             ['sh', "StateHolder"],
00170             ['fk', "ForwardKinematics"],
00171             ['el', "SoftErrorLimiter"],
00172             # ['co', "CollisionDetector"],
00173             ['sc', "ServoController"],
00174             ['log', "DataLogger"]
00175             ]


nextage_ros_bridge
Author(s): Isaac Isao Saito
autogenerated on Mon Oct 6 2014 07:22:37