gripper_command.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # Software License Agreement (BSD License)
4 #
5 # Copyright (c) 2013, Tokyo Opensource Robotics Kyokai Association
6 # All rights reserved.
7 #
8 # Redistribution and use in source and binary forms, with or without
9 # modification, are permitted provided that the following conditions
10 # are met:
11 #
12 # * Redistributions of source code must retain the above copyright
13 # notice, this list of conditions and the following disclaimer.
14 # * Redistributions in binary form must reproduce the above
15 # copyright notice, this list of conditions and the following
16 # disclaimer in the documentation and/or other materials provided
17 # with the distribution.
18 # * Neither the name of Tokyo Opensource Robotics Kyokai Association. nor the
19 # names of its contributors may be used to endorse or promote products
20 # derived from this software without specific prior written permission.
21 #
22 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 # POSSIBILITY OF SUCH DAMAGE.
34 #
35 # Author: Isaac Isao Saito
36 
37 import rospy
38 
39 from abs_hand_command import AbsractHandCommand
40 
41 
42 class GripperCommand(AbsractHandCommand):
43  '''
44  Following Command design pattern, this class represents an abstract
45  command for hand classes of NEXTAGE OPEN.
46 
47  NOTE: 1/31/2014 TODO: Only right hand is implemented for now.
48  '''
49  # TODO: Unittest is needed!!
50 
51  GRIPPER_CLOSE = 'close'
52  GRIPPER_OPEN = 'open'
53  GRIPPER_DANGER = 'danger'
54 
55  def __init__(self, hands, hand, dio_pins):
56  super(GripperCommand, self).__init__(hands, hand, dio_pins)
57 
58  def _assign_dio_names(self, dio_pins):
59  '''
60  @see abs_hand_command.AbsractHandCommand._assign_dio_names
61  '''
62  self._DIO_VALVE_L_1 = dio_pins[0]
63  self._DIO_VALVE_L_2 = dio_pins[1]
64  self._DIO_VALVE_R_1 = dio_pins[2]
65  self._DIO_VALVE_R_2 = dio_pins[3]
66 
67  def execute(self, operation):
68  '''
69  @see abs_hand_command.AbsractHandCommand.execute
70  '''
71  dout = []
72  mask_l = [self._DIO_VALVE_L_1, self._DIO_VALVE_L_2]
73  mask_r = [self._DIO_VALVE_R_1, self._DIO_VALVE_R_2]
74  if self.GRIPPER_CLOSE == operation:
75  if self._hands.HAND_L == self._hand:
76  dout = [self._DIO_VALVE_L_1]
77 
78  elif self._hands.HAND_R == self._hand:
79  dout = [self._DIO_VALVE_R_1]
80  elif self.GRIPPER_OPEN == operation:
81  if self._hands.HAND_L == self._hand:
82  dout = [self._DIO_VALVE_L_2]
83  elif self._hands.HAND_R == self._hand:
84  dout = [self._DIO_VALVE_R_2]
85  mask = None
86  if self._hands.HAND_L == self._hand:
87  mask = mask_l
88  elif self._hands.HAND_R == self._hand:
89  mask = mask_r
90  return self._hands._dio_writer(dout, mask)


nextage_ros_bridge
Author(s): Isaac Isao Saito , Akio Ochiai
autogenerated on Wed Jun 17 2020 04:14:47