hands_05.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # Software License Agreement (BSD License)
00004 #
00005 # Copyright (c) 2014, 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 nextage_ros_bridge.base_hands import BaseHands
00038 from nextage_ros_bridge.command.airhand_command import AbsractHandCommand
00039 from nextage_ros_bridge.command.airhand_command import AirhandCommand
00040 from nextage_ros_bridge.command.gripper_command import GripperCommand
00041 from nextage_ros_bridge.command.handlight_command import HandlightCommand
00042 from nextage_ros_bridge.command.toolchanger_command import ToolchangerCommand
00043 
00044 
00045 class Hands05(BaseHands):
00046     '''
00047     This class holds methods to operate the hands of NEXTAGE OPEN, based on the
00048     specification of the robot made by the manufacturer (Kawada)
00049     in August 2014 and thereafter.
00050 
00051     For the robot shipped before then, use Iros13Hands.
00052     '''
00053 
00054     def __init__(self, parent):
00055         '''
00056         @see: AbsractIros13Hands.__init__
00057         '''
00058         # Instantiating public command classes.
00059         #
00060         # There can be at least 2 ways for the Robot client classes
00061         # (eg. See nextage_client.NextageClient) to call hand commands.
00062         #
00063         #  (1) Call directly the 'execute' methods of each command.
00064         #  (2) Call via interface methods in the hand class.
00065         #
00066         # In this class, (1) is used. (1) is faster to implement. And
00067         # I think it's ok for robot client classes to know what commands exist,
00068         # without the hand class has the interfaces for commands. But you can
00069         # always apply (2) approach, which is cleaner.
00070         super(Hands05, self).__init__(parent)
00071         _pins_airhand = [self.DIO_27, self.DIO_28, self.DIO_25, self.DIO_26]
00072         _pins_gripper = [self.DIO_23, self.DIO_24, self.DIO_21, self.DIO_22]
00073         _pins_handlight = [self.DIO_18, self.DIO_17]
00074         _pins_toolchanger = [self.DIO_20, self.DIO_27, self.DIO_28,  # L-hand
00075                              self.DIO_19, self.DIO_25, self.DIO_26]  # R-hand
00076 
00077         self._airhand_l_command = AirhandCommand(self, self.HAND_L, _pins_airhand)
00078         self._airhand_r_command = AirhandCommand(self, self.HAND_R, _pins_airhand)
00079         self._gripper_l_command = GripperCommand(self, self.HAND_L, _pins_gripper)
00080         self._gripper_r_command = GripperCommand(self, self.HAND_R, _pins_gripper)
00081 
00082         # The following lines are moved from BaseToolchangerHands
00083         self._handlight_l_command = HandlightCommand(self, self.HAND_L, _pins_handlight)
00084         self._handlight_r_command = HandlightCommand(self, self.HAND_R, _pins_handlight)
00085         self._toolchanger_l_command = ToolchangerCommand(self, self.HAND_L, _pins_toolchanger)
00086         self._toolchanger_r_command = ToolchangerCommand(self, self.HAND_R, _pins_toolchanger)
00087 
00088     def airhand_l_drawin(self):
00089         return self._airhand_l_command.execute(self._airhand_l_command.AIRHAND_DRAWIN)
00090 
00091     def airhand_r_drawin(self):
00092         return self._airhand_r_command.execute(self._airhand_r_command.AIRHAND_DRAWIN)
00093 
00094     def airhand_l_keep(self):
00095         return self._airhand_l_command.execute(self._airhand_l_command.AIRHAND_KEEP)
00096 
00097     def airhand_r_keep(self):
00098         return self._airhand_r_command.execute(self._airhand_r_command.AIRHAND_KEEP)
00099 
00100     def airhand_l_release(self):
00101         return self._airhand_l_command.execute(self._airhand_l_command.AIRHAND_RELEASE)
00102 
00103     def airhand_r_release(self):
00104         return self._airhand_r_command.execute(self._airhand_r_command.AIRHAND_RELEASE)
00105 
00106     def gripper_l_close(self):
00107         return self._gripper_l_command.execute(self._gripper_l_command.GRIPPER_CLOSE)
00108 
00109     def gripper_r_close(self):
00110         return self._gripper_r_command.execute(self._gripper_r_command.GRIPPER_CLOSE)
00111 
00112     def gripper_l_open(self):
00113         return self._gripper_l_command.execute(self._gripper_r_command.GRIPPER_OPEN)
00114 
00115     def gripper_r_open(self):
00116         return self._gripper_r_command.execute(self._gripper_r_command.GRIPPER_OPEN)
00117 
00118     def handtool_l_eject(self):
00119         return self._toolchanger_l_command.execute(
00120             self._toolchanger_l_command.HAND_TOOLCHANGE_OFF)
00121 
00122     def handtool_r_eject(self):
00123         return self._toolchanger_r_command.execute(
00124             self._toolchanger_r_command.HAND_TOOLCHANGE_OFF)
00125 
00126     def handtool_l_attach(self):
00127         return self._toolchanger_l_command.execute(
00128             self._toolchanger_l_command.HAND_TOOLCHANGE_ON)
00129 
00130     def handtool_r_attach(self):
00131         return self._toolchanger_r_command.execute(
00132             self._toolchanger_r_command.HAND_TOOLCHANGE_ON)
00133 
00134     def handlight_r(self, is_on=True):
00135         return self._handlight_r_command.turn_handlight(self.HAND_R, is_on)
00136 
00137     def handlight_l(self, is_on=True):
00138         return self._handlight_l_command.turn_handlight(self.HAND_L, is_on)
00139 
00140     def handlight_both(self, is_on=True):
00141         result = self._handlight_l_command.turn_handlight(self.HAND_L, is_on)
00142         result = self._handlight_r_command.turn_handlight(self.HAND_R, is_on) and result
00143         return result


nextage_ros_bridge
Author(s): Isaac Isao Saito , Akio Ochiai
autogenerated on Wed May 15 2019 04:45:36