iros13_hands.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 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 Iros13Hands(BaseHands):
00046     '''
00047     This class holds methods to operate the hands of NEXTAGE OPEN in a specific
00048     configuration where a clipping hand on left and suction hand on right
00049     connected to toolchanger module. This was presented at IROS 2013.
00050     '''
00051     # TODO: Unittest is needed!!
00052 
00053     def __init__(self, parent):
00054         '''
00055         @see: AbsractIros13Hands.__init__
00056         '''
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 Iros13Hands 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 comamands. But you can
00069         # always apply (2) approach, which is cleaner.
00070         super(Iros13Hands, self).__init__(parent)
00071         _pins_airhand = [self.DIO_27, self.DIO_28, self.DIO_22, self.DIO_23]
00072         _pins_gripper = [self.DIO_25, self.DIO_26, self.DIO_20, self.DIO_21]
00073         self.airhand_l_command = AirhandCommand(self, self.HAND_L, _pins_airhand)
00074         self.airhand_r_command = AirhandCommand(self, self.HAND_R, _pins_airhand)
00075         self.gripper_l_command = GripperCommand(self, self.HAND_L, _pins_gripper)
00076         self.gripper_r_command = GripperCommand(self, self.HAND_R, _pins_gripper)
00077 
00078         _pins_handlight = [self.DIO_18, self.DIO_17]
00079         _pins_toolchanger = [self.DIO_24, self.DIO_25, self.DIO_26,
00080                              self.DIO_19, self.DIO_20, self.DIO_21]
00081         # The following lines are moved from BaseToolchangerHands
00082         self.handlight_l_command = HandlightCommand(self, self.HAND_L, _pins_handlight)
00083         self.handlight_r_command = HandlightCommand(self, self.HAND_R, _pins_handlight)
00084         self.toolchanger_l_command = ToolchangerCommand(self, self.HAND_L, _pins_toolchanger)
00085         self.toolchanger_r_command = ToolchangerCommand(self, self.HAND_R, _pins_toolchanger)
00086 
00087     def airhand_l_drawin(self):
00088         return self.airhand_l_command.execute(self.airhand_l_command.AIRHAND_DRAWIN)
00089 
00090     def airhand_r_drawin(self):
00091         return self.airhand_r_command.execute(self.airhand_r_command.AIRHAND_DRAWIN)
00092 
00093     def airhand_l_keep(self):
00094         return self.airhand_l_command.execute(self.airhand_l_command.AIRHAND_KEEP)
00095 
00096     def airhand_r_keep(self):
00097         return self.airhand_r_command.execute(self.airhand_r_command.AIRHAND_KEEP)
00098 
00099     def airhand_l_release(self):
00100         return self.airhand_l_command.execute(self.airhand_l_command.AIRHAND_RELEASE)
00101 
00102     def airhand_r_release(self):
00103         return self.airhand_r_command.execute(self.airhand_r_command.AIRHAND_RELEASE)
00104 
00105     def gripper_l_close(self):
00106         return self.gripper_l_command.execute(self.gripper_l_command.GRIPPER_CLOSE)
00107 
00108     def gripper_r_close(self):
00109         return self.gripper_r_command.execute(self.gripper_r_command.GRIPPER_CLOSE)
00110 
00111     def gripper_l_open(self):
00112         return self.gripper_l_command.execute(self.gripper_r_command.GRIPPER_OPEN)
00113 
00114     def gripper_r_open(self):
00115         return self.gripper_r_command.execute(self.gripper_r_command.GRIPPER_OPEN)
00116 
00117     def handtool_l_eject(self):
00118         return self.toolchanger_l_command.execute(
00119             self.toolchanger_l_command.HAND_TOOLCHANGE_OFF)
00120 
00121     def handtool_r_eject(self):
00122         return self.toolchanger_r_command.execute(
00123             self.toolchanger_r_command.HAND_TOOLCHANGE_OFF)
00124 
00125     def handtool_l_attach(self):
00126         return self.toolchanger_l_command.execute(
00127             self.toolchanger_l_command.HAND_TOOLCHANGE_ON)
00128 
00129     def handtool_r_attach(self):
00130         return self.toolchanger_r_command.execute(
00131             self.toolchanger_r_command.HAND_TOOLCHANGE_ON)
00132 
00133     def handlight_r(self, is_on=True):
00134         return self.handlight_r_command.turn_handlight(self.HAND_R, is_on)
00135 
00136     def handlight_l(self, is_on=True):
00137         return self.handlight_l_command.turn_handlight(self.HAND_L, is_on)
00138 
00139     def handlight_both(self, is_on=True):
00140         result = self.handlight_l_command.turn_handlight(self.HAND_L, is_on)
00141         result = result and self.handlight_r_command.turn_handlight(self.HAND_R, is_on)
00142         return result


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