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