$search
00001 """autogenerated by genmsg_py from ReactiveGraspingActionGoal.msg. Do not edit.""" 00002 import roslib.message 00003 import struct 00004 00005 import srs_assisted_grasping_msgs.msg 00006 import roslib.rostime 00007 import actionlib_msgs.msg 00008 import std_msgs.msg 00009 00010 class ReactiveGraspingActionGoal(roslib.message.Message): 00011 _md5sum = "c03a7d12fba227b4d0883fda55c9e43a" 00012 _type = "srs_assisted_grasping_msgs/ReactiveGraspingActionGoal" 00013 _has_header = True #flag to mark the presence of a Header object 00014 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00015 00016 Header header 00017 actionlib_msgs/GoalID goal_id 00018 ReactiveGraspingGoal goal 00019 00020 ================================================================================ 00021 MSG: std_msgs/Header 00022 # Standard metadata for higher-level stamped data types. 00023 # This is generally used to communicate timestamped data 00024 # in a particular coordinate frame. 00025 # 00026 # sequence ID: consecutively increasing ID 00027 uint32 seq 00028 #Two-integer timestamp that is expressed as: 00029 # * stamp.secs: seconds (stamp_secs) since epoch 00030 # * stamp.nsecs: nanoseconds since stamp_secs 00031 # time-handling sugar is provided by the client library 00032 time stamp 00033 #Frame this data is associated with 00034 # 0: no frame 00035 # 1: global frame 00036 string frame_id 00037 00038 ================================================================================ 00039 MSG: actionlib_msgs/GoalID 00040 # The stamp should store the time at which this goal was requested. 00041 # It is used by an action server when it tries to preempt all 00042 # goals that were requested before a certain time 00043 time stamp 00044 00045 # The id provides a way to associate feedback and 00046 # result message with specific goal requests. The id 00047 # specified must be unique. 00048 string id 00049 00050 00051 ================================================================================ 00052 MSG: srs_assisted_grasping_msgs/ReactiveGraspingGoal 00053 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ====== 00054 # GOAL 00055 std_msgs/Float32MultiArray target_configuration # n joints, 7 for SDH (names should be specified in yaml file) 00056 std_msgs/Float32MultiArray max_force # m tactile pads 00057 duration time # time to reach target_configuration 00058 00059 ================================================================================ 00060 MSG: std_msgs/Float32MultiArray 00061 # Please look at the MultiArrayLayout message definition for 00062 # documentation on all multiarrays. 00063 00064 MultiArrayLayout layout # specification of data layout 00065 float32[] data # array of data 00066 00067 00068 ================================================================================ 00069 MSG: std_msgs/MultiArrayLayout 00070 # The multiarray declares a generic multi-dimensional array of a 00071 # particular data type. Dimensions are ordered from outer most 00072 # to inner most. 00073 00074 MultiArrayDimension[] dim # Array of dimension properties 00075 uint32 data_offset # padding bytes at front of data 00076 00077 # Accessors should ALWAYS be written in terms of dimension stride 00078 # and specified outer-most dimension first. 00079 # 00080 # multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] 00081 # 00082 # A standard, 3-channel 640x480 image with interleaved color channels 00083 # would be specified as: 00084 # 00085 # dim[0].label = "height" 00086 # dim[0].size = 480 00087 # dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) 00088 # dim[1].label = "width" 00089 # dim[1].size = 640 00090 # dim[1].stride = 3*640 = 1920 00091 # dim[2].label = "channel" 00092 # dim[2].size = 3 00093 # dim[2].stride = 3 00094 # 00095 # multiarray(i,j,k) refers to the ith row, jth column, and kth channel. 00096 ================================================================================ 00097 MSG: std_msgs/MultiArrayDimension 00098 string label # label of given dimension 00099 uint32 size # size of given dimension (in type units) 00100 uint32 stride # stride of given dimension 00101 """ 00102 __slots__ = ['header','goal_id','goal'] 00103 _slot_types = ['Header','actionlib_msgs/GoalID','srs_assisted_grasping_msgs/ReactiveGraspingGoal'] 00104 00105 def __init__(self, *args, **kwds): 00106 """ 00107 Constructor. Any message fields that are implicitly/explicitly 00108 set to None will be assigned a default value. The recommend 00109 use is keyword arguments as this is more robust to future message 00110 changes. You cannot mix in-order arguments and keyword arguments. 00111 00112 The available fields are: 00113 header,goal_id,goal 00114 00115 @param args: complete set of field values, in .msg order 00116 @param kwds: use keyword arguments corresponding to message field names 00117 to set specific fields. 00118 """ 00119 if args or kwds: 00120 super(ReactiveGraspingActionGoal, self).__init__(*args, **kwds) 00121 #message fields cannot be None, assign default values for those that are 00122 if self.header is None: 00123 self.header = std_msgs.msg._Header.Header() 00124 if self.goal_id is None: 00125 self.goal_id = actionlib_msgs.msg.GoalID() 00126 if self.goal is None: 00127 self.goal = srs_assisted_grasping_msgs.msg.ReactiveGraspingGoal() 00128 else: 00129 self.header = std_msgs.msg._Header.Header() 00130 self.goal_id = actionlib_msgs.msg.GoalID() 00131 self.goal = srs_assisted_grasping_msgs.msg.ReactiveGraspingGoal() 00132 00133 def _get_types(self): 00134 """ 00135 internal API method 00136 """ 00137 return self._slot_types 00138 00139 def serialize(self, buff): 00140 """ 00141 serialize message into buffer 00142 @param buff: buffer 00143 @type buff: StringIO 00144 """ 00145 try: 00146 _x = self 00147 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs)) 00148 _x = self.header.frame_id 00149 length = len(_x) 00150 buff.write(struct.pack('<I%ss'%length, length, _x)) 00151 _x = self 00152 buff.write(_struct_2I.pack(_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs)) 00153 _x = self.goal_id.id 00154 length = len(_x) 00155 buff.write(struct.pack('<I%ss'%length, length, _x)) 00156 length = len(self.goal.target_configuration.layout.dim) 00157 buff.write(_struct_I.pack(length)) 00158 for val1 in self.goal.target_configuration.layout.dim: 00159 _x = val1.label 00160 length = len(_x) 00161 buff.write(struct.pack('<I%ss'%length, length, _x)) 00162 _x = val1 00163 buff.write(_struct_2I.pack(_x.size, _x.stride)) 00164 buff.write(_struct_I.pack(self.goal.target_configuration.layout.data_offset)) 00165 length = len(self.goal.target_configuration.data) 00166 buff.write(_struct_I.pack(length)) 00167 pattern = '<%sf'%length 00168 buff.write(struct.pack(pattern, *self.goal.target_configuration.data)) 00169 length = len(self.goal.max_force.layout.dim) 00170 buff.write(_struct_I.pack(length)) 00171 for val1 in self.goal.max_force.layout.dim: 00172 _x = val1.label 00173 length = len(_x) 00174 buff.write(struct.pack('<I%ss'%length, length, _x)) 00175 _x = val1 00176 buff.write(_struct_2I.pack(_x.size, _x.stride)) 00177 buff.write(_struct_I.pack(self.goal.max_force.layout.data_offset)) 00178 length = len(self.goal.max_force.data) 00179 buff.write(_struct_I.pack(length)) 00180 pattern = '<%sf'%length 00181 buff.write(struct.pack(pattern, *self.goal.max_force.data)) 00182 _x = self 00183 buff.write(_struct_2i.pack(_x.goal.time.secs, _x.goal.time.nsecs)) 00184 except struct.error as se: self._check_types(se) 00185 except TypeError as te: self._check_types(te) 00186 00187 def deserialize(self, str): 00188 """ 00189 unpack serialized message in str into this message instance 00190 @param str: byte array of serialized message 00191 @type str: str 00192 """ 00193 try: 00194 if self.header is None: 00195 self.header = std_msgs.msg._Header.Header() 00196 if self.goal_id is None: 00197 self.goal_id = actionlib_msgs.msg.GoalID() 00198 if self.goal is None: 00199 self.goal = srs_assisted_grasping_msgs.msg.ReactiveGraspingGoal() 00200 end = 0 00201 _x = self 00202 start = end 00203 end += 12 00204 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00205 start = end 00206 end += 4 00207 (length,) = _struct_I.unpack(str[start:end]) 00208 start = end 00209 end += length 00210 self.header.frame_id = str[start:end] 00211 _x = self 00212 start = end 00213 end += 8 00214 (_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00215 start = end 00216 end += 4 00217 (length,) = _struct_I.unpack(str[start:end]) 00218 start = end 00219 end += length 00220 self.goal_id.id = str[start:end] 00221 start = end 00222 end += 4 00223 (length,) = _struct_I.unpack(str[start:end]) 00224 self.goal.target_configuration.layout.dim = [] 00225 for i in range(0, length): 00226 val1 = std_msgs.msg.MultiArrayDimension() 00227 start = end 00228 end += 4 00229 (length,) = _struct_I.unpack(str[start:end]) 00230 start = end 00231 end += length 00232 val1.label = str[start:end] 00233 _x = val1 00234 start = end 00235 end += 8 00236 (_x.size, _x.stride,) = _struct_2I.unpack(str[start:end]) 00237 self.goal.target_configuration.layout.dim.append(val1) 00238 start = end 00239 end += 4 00240 (self.goal.target_configuration.layout.data_offset,) = _struct_I.unpack(str[start:end]) 00241 start = end 00242 end += 4 00243 (length,) = _struct_I.unpack(str[start:end]) 00244 pattern = '<%sf'%length 00245 start = end 00246 end += struct.calcsize(pattern) 00247 self.goal.target_configuration.data = struct.unpack(pattern, str[start:end]) 00248 start = end 00249 end += 4 00250 (length,) = _struct_I.unpack(str[start:end]) 00251 self.goal.max_force.layout.dim = [] 00252 for i in range(0, length): 00253 val1 = std_msgs.msg.MultiArrayDimension() 00254 start = end 00255 end += 4 00256 (length,) = _struct_I.unpack(str[start:end]) 00257 start = end 00258 end += length 00259 val1.label = str[start:end] 00260 _x = val1 00261 start = end 00262 end += 8 00263 (_x.size, _x.stride,) = _struct_2I.unpack(str[start:end]) 00264 self.goal.max_force.layout.dim.append(val1) 00265 start = end 00266 end += 4 00267 (self.goal.max_force.layout.data_offset,) = _struct_I.unpack(str[start:end]) 00268 start = end 00269 end += 4 00270 (length,) = _struct_I.unpack(str[start:end]) 00271 pattern = '<%sf'%length 00272 start = end 00273 end += struct.calcsize(pattern) 00274 self.goal.max_force.data = struct.unpack(pattern, str[start:end]) 00275 _x = self 00276 start = end 00277 end += 8 00278 (_x.goal.time.secs, _x.goal.time.nsecs,) = _struct_2i.unpack(str[start:end]) 00279 return self 00280 except struct.error as e: 00281 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00282 00283 00284 def serialize_numpy(self, buff, numpy): 00285 """ 00286 serialize message with numpy array types into buffer 00287 @param buff: buffer 00288 @type buff: StringIO 00289 @param numpy: numpy python module 00290 @type numpy module 00291 """ 00292 try: 00293 _x = self 00294 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs)) 00295 _x = self.header.frame_id 00296 length = len(_x) 00297 buff.write(struct.pack('<I%ss'%length, length, _x)) 00298 _x = self 00299 buff.write(_struct_2I.pack(_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs)) 00300 _x = self.goal_id.id 00301 length = len(_x) 00302 buff.write(struct.pack('<I%ss'%length, length, _x)) 00303 length = len(self.goal.target_configuration.layout.dim) 00304 buff.write(_struct_I.pack(length)) 00305 for val1 in self.goal.target_configuration.layout.dim: 00306 _x = val1.label 00307 length = len(_x) 00308 buff.write(struct.pack('<I%ss'%length, length, _x)) 00309 _x = val1 00310 buff.write(_struct_2I.pack(_x.size, _x.stride)) 00311 buff.write(_struct_I.pack(self.goal.target_configuration.layout.data_offset)) 00312 length = len(self.goal.target_configuration.data) 00313 buff.write(_struct_I.pack(length)) 00314 pattern = '<%sf'%length 00315 buff.write(self.goal.target_configuration.data.tostring()) 00316 length = len(self.goal.max_force.layout.dim) 00317 buff.write(_struct_I.pack(length)) 00318 for val1 in self.goal.max_force.layout.dim: 00319 _x = val1.label 00320 length = len(_x) 00321 buff.write(struct.pack('<I%ss'%length, length, _x)) 00322 _x = val1 00323 buff.write(_struct_2I.pack(_x.size, _x.stride)) 00324 buff.write(_struct_I.pack(self.goal.max_force.layout.data_offset)) 00325 length = len(self.goal.max_force.data) 00326 buff.write(_struct_I.pack(length)) 00327 pattern = '<%sf'%length 00328 buff.write(self.goal.max_force.data.tostring()) 00329 _x = self 00330 buff.write(_struct_2i.pack(_x.goal.time.secs, _x.goal.time.nsecs)) 00331 except struct.error as se: self._check_types(se) 00332 except TypeError as te: self._check_types(te) 00333 00334 def deserialize_numpy(self, str, numpy): 00335 """ 00336 unpack serialized message in str into this message instance using numpy for array types 00337 @param str: byte array of serialized message 00338 @type str: str 00339 @param numpy: numpy python module 00340 @type numpy: module 00341 """ 00342 try: 00343 if self.header is None: 00344 self.header = std_msgs.msg._Header.Header() 00345 if self.goal_id is None: 00346 self.goal_id = actionlib_msgs.msg.GoalID() 00347 if self.goal is None: 00348 self.goal = srs_assisted_grasping_msgs.msg.ReactiveGraspingGoal() 00349 end = 0 00350 _x = self 00351 start = end 00352 end += 12 00353 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00354 start = end 00355 end += 4 00356 (length,) = _struct_I.unpack(str[start:end]) 00357 start = end 00358 end += length 00359 self.header.frame_id = str[start:end] 00360 _x = self 00361 start = end 00362 end += 8 00363 (_x.goal_id.stamp.secs, _x.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end]) 00364 start = end 00365 end += 4 00366 (length,) = _struct_I.unpack(str[start:end]) 00367 start = end 00368 end += length 00369 self.goal_id.id = str[start:end] 00370 start = end 00371 end += 4 00372 (length,) = _struct_I.unpack(str[start:end]) 00373 self.goal.target_configuration.layout.dim = [] 00374 for i in range(0, length): 00375 val1 = std_msgs.msg.MultiArrayDimension() 00376 start = end 00377 end += 4 00378 (length,) = _struct_I.unpack(str[start:end]) 00379 start = end 00380 end += length 00381 val1.label = str[start:end] 00382 _x = val1 00383 start = end 00384 end += 8 00385 (_x.size, _x.stride,) = _struct_2I.unpack(str[start:end]) 00386 self.goal.target_configuration.layout.dim.append(val1) 00387 start = end 00388 end += 4 00389 (self.goal.target_configuration.layout.data_offset,) = _struct_I.unpack(str[start:end]) 00390 start = end 00391 end += 4 00392 (length,) = _struct_I.unpack(str[start:end]) 00393 pattern = '<%sf'%length 00394 start = end 00395 end += struct.calcsize(pattern) 00396 self.goal.target_configuration.data = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length) 00397 start = end 00398 end += 4 00399 (length,) = _struct_I.unpack(str[start:end]) 00400 self.goal.max_force.layout.dim = [] 00401 for i in range(0, length): 00402 val1 = std_msgs.msg.MultiArrayDimension() 00403 start = end 00404 end += 4 00405 (length,) = _struct_I.unpack(str[start:end]) 00406 start = end 00407 end += length 00408 val1.label = str[start:end] 00409 _x = val1 00410 start = end 00411 end += 8 00412 (_x.size, _x.stride,) = _struct_2I.unpack(str[start:end]) 00413 self.goal.max_force.layout.dim.append(val1) 00414 start = end 00415 end += 4 00416 (self.goal.max_force.layout.data_offset,) = _struct_I.unpack(str[start:end]) 00417 start = end 00418 end += 4 00419 (length,) = _struct_I.unpack(str[start:end]) 00420 pattern = '<%sf'%length 00421 start = end 00422 end += struct.calcsize(pattern) 00423 self.goal.max_force.data = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length) 00424 _x = self 00425 start = end 00426 end += 8 00427 (_x.goal.time.secs, _x.goal.time.nsecs,) = _struct_2i.unpack(str[start:end]) 00428 return self 00429 except struct.error as e: 00430 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00431 00432 _struct_I = roslib.message.struct_I 00433 _struct_3I = struct.Struct("<3I") 00434 _struct_2I = struct.Struct("<2I") 00435 _struct_2i = struct.Struct("<2i")