$search
00001 """autogenerated by genmsg_py from ArmAction.msg. Do not edit.""" 00002 import roslib.message 00003 import struct 00004 00005 import geometry_msgs.msg 00006 import roslib.rostime 00007 00008 class ArmAction(roslib.message.Message): 00009 _md5sum = "3cbdbdb85ac6ff6f8288425d4a1dec78" 00010 _type = "simple_arm_server/ArmAction" 00011 _has_header = False #flag to mark the presence of a Header object 00012 _full_text = """# 00013 # Move arm or adjust gripper 00014 # 00015 00016 byte MOVE_ARM=0 00017 byte MOVE_GRIPPER=1 00018 00019 byte type # move the arm or the gripper? 00020 00021 geometry_msgs/Pose goal # goal for arm 00022 float64 command # width to open gripper 00023 00024 duration move_time 00025 00026 ================================================================================ 00027 MSG: geometry_msgs/Pose 00028 # A representation of pose in free space, composed of postion and orientation. 00029 Point position 00030 Quaternion orientation 00031 00032 ================================================================================ 00033 MSG: geometry_msgs/Point 00034 # This contains the position of a point in free space 00035 float64 x 00036 float64 y 00037 float64 z 00038 00039 ================================================================================ 00040 MSG: geometry_msgs/Quaternion 00041 # This represents an orientation in free space in quaternion form. 00042 00043 float64 x 00044 float64 y 00045 float64 z 00046 float64 w 00047 00048 """ 00049 # Pseudo-constants 00050 MOVE_ARM = 0 00051 MOVE_GRIPPER = 1 00052 00053 __slots__ = ['type','goal','command','move_time'] 00054 _slot_types = ['byte','geometry_msgs/Pose','float64','duration'] 00055 00056 def __init__(self, *args, **kwds): 00057 """ 00058 Constructor. Any message fields that are implicitly/explicitly 00059 set to None will be assigned a default value. The recommend 00060 use is keyword arguments as this is more robust to future message 00061 changes. You cannot mix in-order arguments and keyword arguments. 00062 00063 The available fields are: 00064 type,goal,command,move_time 00065 00066 @param args: complete set of field values, in .msg order 00067 @param kwds: use keyword arguments corresponding to message field names 00068 to set specific fields. 00069 """ 00070 if args or kwds: 00071 super(ArmAction, self).__init__(*args, **kwds) 00072 #message fields cannot be None, assign default values for those that are 00073 if self.type is None: 00074 self.type = 0 00075 if self.goal is None: 00076 self.goal = geometry_msgs.msg.Pose() 00077 if self.command is None: 00078 self.command = 0. 00079 if self.move_time is None: 00080 self.move_time = roslib.rostime.Duration() 00081 else: 00082 self.type = 0 00083 self.goal = geometry_msgs.msg.Pose() 00084 self.command = 0. 00085 self.move_time = roslib.rostime.Duration() 00086 00087 def _get_types(self): 00088 """ 00089 internal API method 00090 """ 00091 return self._slot_types 00092 00093 def serialize(self, buff): 00094 """ 00095 serialize message into buffer 00096 @param buff: buffer 00097 @type buff: StringIO 00098 """ 00099 try: 00100 _x = self 00101 buff.write(_struct_b8d2i.pack(_x.type, _x.goal.position.x, _x.goal.position.y, _x.goal.position.z, _x.goal.orientation.x, _x.goal.orientation.y, _x.goal.orientation.z, _x.goal.orientation.w, _x.command, _x.move_time.secs, _x.move_time.nsecs)) 00102 except struct.error as se: self._check_types(se) 00103 except TypeError as te: self._check_types(te) 00104 00105 def deserialize(self, str): 00106 """ 00107 unpack serialized message in str into this message instance 00108 @param str: byte array of serialized message 00109 @type str: str 00110 """ 00111 try: 00112 if self.goal is None: 00113 self.goal = geometry_msgs.msg.Pose() 00114 if self.move_time is None: 00115 self.move_time = roslib.rostime.Duration() 00116 end = 0 00117 _x = self 00118 start = end 00119 end += 73 00120 (_x.type, _x.goal.position.x, _x.goal.position.y, _x.goal.position.z, _x.goal.orientation.x, _x.goal.orientation.y, _x.goal.orientation.z, _x.goal.orientation.w, _x.command, _x.move_time.secs, _x.move_time.nsecs,) = _struct_b8d2i.unpack(str[start:end]) 00121 self.move_time.canon() 00122 return self 00123 except struct.error as e: 00124 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00125 00126 00127 def serialize_numpy(self, buff, numpy): 00128 """ 00129 serialize message with numpy array types into buffer 00130 @param buff: buffer 00131 @type buff: StringIO 00132 @param numpy: numpy python module 00133 @type numpy module 00134 """ 00135 try: 00136 _x = self 00137 buff.write(_struct_b8d2i.pack(_x.type, _x.goal.position.x, _x.goal.position.y, _x.goal.position.z, _x.goal.orientation.x, _x.goal.orientation.y, _x.goal.orientation.z, _x.goal.orientation.w, _x.command, _x.move_time.secs, _x.move_time.nsecs)) 00138 except struct.error as se: self._check_types(se) 00139 except TypeError as te: self._check_types(te) 00140 00141 def deserialize_numpy(self, str, numpy): 00142 """ 00143 unpack serialized message in str into this message instance using numpy for array types 00144 @param str: byte array of serialized message 00145 @type str: str 00146 @param numpy: numpy python module 00147 @type numpy: module 00148 """ 00149 try: 00150 if self.goal is None: 00151 self.goal = geometry_msgs.msg.Pose() 00152 if self.move_time is None: 00153 self.move_time = roslib.rostime.Duration() 00154 end = 0 00155 _x = self 00156 start = end 00157 end += 73 00158 (_x.type, _x.goal.position.x, _x.goal.position.y, _x.goal.position.z, _x.goal.orientation.x, _x.goal.orientation.y, _x.goal.orientation.z, _x.goal.orientation.w, _x.command, _x.move_time.secs, _x.move_time.nsecs,) = _struct_b8d2i.unpack(str[start:end]) 00159 self.move_time.canon() 00160 return self 00161 except struct.error as e: 00162 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00163 00164 _struct_I = roslib.message.struct_I 00165 _struct_b8d2i = struct.Struct("<b8d2i")