00001 """autogenerated by genpy from pr2_gazebo_plugins/SetModelsJointsStatesRequest.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 pr2_gazebo_plugins.msg
00008 import geometry_msgs.msg
00009
00010 class SetModelsJointsStatesRequest(genpy.Message):
00011 _md5sum = "ecf71b483df7b70447575a8231727200"
00012 _type = "pr2_gazebo_plugins/SetModelsJointsStatesRequest"
00013 _has_header = False
00014 _full_text = """string[] model_names
00015 pr2_gazebo_plugins/ModelJointsState[] model_joints_states
00016
00017 ================================================================================
00018 MSG: pr2_gazebo_plugins/ModelJointsState
00019 geometry_msgs/Pose[] model_pose # set as single element array if user wishes to specify model pose, otherwise, leave empty
00020 string[] joint_names # list of joint names
00021 float64[] joint_positions # list of desired joint positions, should match joint_names
00022
00023 ================================================================================
00024 MSG: geometry_msgs/Pose
00025 # A representation of pose in free space, composed of postion and orientation.
00026 Point position
00027 Quaternion orientation
00028
00029 ================================================================================
00030 MSG: geometry_msgs/Point
00031 # This contains the position of a point in free space
00032 float64 x
00033 float64 y
00034 float64 z
00035
00036 ================================================================================
00037 MSG: geometry_msgs/Quaternion
00038 # This represents an orientation in free space in quaternion form.
00039
00040 float64 x
00041 float64 y
00042 float64 z
00043 float64 w
00044
00045 """
00046 __slots__ = ['model_names','model_joints_states']
00047 _slot_types = ['string[]','pr2_gazebo_plugins/ModelJointsState[]']
00048
00049 def __init__(self, *args, **kwds):
00050 """
00051 Constructor. Any message fields that are implicitly/explicitly
00052 set to None will be assigned a default value. The recommend
00053 use is keyword arguments as this is more robust to future message
00054 changes. You cannot mix in-order arguments and keyword arguments.
00055
00056 The available fields are:
00057 model_names,model_joints_states
00058
00059 :param args: complete set of field values, in .msg order
00060 :param kwds: use keyword arguments corresponding to message field names
00061 to set specific fields.
00062 """
00063 if args or kwds:
00064 super(SetModelsJointsStatesRequest, self).__init__(*args, **kwds)
00065
00066 if self.model_names is None:
00067 self.model_names = []
00068 if self.model_joints_states is None:
00069 self.model_joints_states = []
00070 else:
00071 self.model_names = []
00072 self.model_joints_states = []
00073
00074 def _get_types(self):
00075 """
00076 internal API method
00077 """
00078 return self._slot_types
00079
00080 def serialize(self, buff):
00081 """
00082 serialize message into buffer
00083 :param buff: buffer, ``StringIO``
00084 """
00085 try:
00086 length = len(self.model_names)
00087 buff.write(_struct_I.pack(length))
00088 for val1 in self.model_names:
00089 length = len(val1)
00090 if python3 or type(val1) == unicode:
00091 val1 = val1.encode('utf-8')
00092 length = len(val1)
00093 buff.write(struct.pack('<I%ss'%length, length, val1))
00094 length = len(self.model_joints_states)
00095 buff.write(_struct_I.pack(length))
00096 for val1 in self.model_joints_states:
00097 length = len(val1.model_pose)
00098 buff.write(_struct_I.pack(length))
00099 for val2 in val1.model_pose:
00100 _v1 = val2.position
00101 _x = _v1
00102 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00103 _v2 = val2.orientation
00104 _x = _v2
00105 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00106 length = len(val1.joint_names)
00107 buff.write(_struct_I.pack(length))
00108 for val2 in val1.joint_names:
00109 length = len(val2)
00110 if python3 or type(val2) == unicode:
00111 val2 = val2.encode('utf-8')
00112 length = len(val2)
00113 buff.write(struct.pack('<I%ss'%length, length, val2))
00114 length = len(val1.joint_positions)
00115 buff.write(_struct_I.pack(length))
00116 pattern = '<%sd'%length
00117 buff.write(struct.pack(pattern, *val1.joint_positions))
00118 except struct.error as se: self._check_types(se)
00119 except TypeError as te: self._check_types(te)
00120
00121 def deserialize(self, str):
00122 """
00123 unpack serialized message in str into this message instance
00124 :param str: byte array of serialized message, ``str``
00125 """
00126 try:
00127 if self.model_joints_states is None:
00128 self.model_joints_states = None
00129 end = 0
00130 start = end
00131 end += 4
00132 (length,) = _struct_I.unpack(str[start:end])
00133 self.model_names = []
00134 for i in range(0, length):
00135 start = end
00136 end += 4
00137 (length,) = _struct_I.unpack(str[start:end])
00138 start = end
00139 end += length
00140 if python3:
00141 val1 = str[start:end].decode('utf-8')
00142 else:
00143 val1 = str[start:end]
00144 self.model_names.append(val1)
00145 start = end
00146 end += 4
00147 (length,) = _struct_I.unpack(str[start:end])
00148 self.model_joints_states = []
00149 for i in range(0, length):
00150 val1 = pr2_gazebo_plugins.msg.ModelJointsState()
00151 start = end
00152 end += 4
00153 (length,) = _struct_I.unpack(str[start:end])
00154 val1.model_pose = []
00155 for i in range(0, length):
00156 val2 = geometry_msgs.msg.Pose()
00157 _v3 = val2.position
00158 _x = _v3
00159 start = end
00160 end += 24
00161 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00162 _v4 = val2.orientation
00163 _x = _v4
00164 start = end
00165 end += 32
00166 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00167 val1.model_pose.append(val2)
00168 start = end
00169 end += 4
00170 (length,) = _struct_I.unpack(str[start:end])
00171 val1.joint_names = []
00172 for i in range(0, length):
00173 start = end
00174 end += 4
00175 (length,) = _struct_I.unpack(str[start:end])
00176 start = end
00177 end += length
00178 if python3:
00179 val2 = str[start:end].decode('utf-8')
00180 else:
00181 val2 = str[start:end]
00182 val1.joint_names.append(val2)
00183 start = end
00184 end += 4
00185 (length,) = _struct_I.unpack(str[start:end])
00186 pattern = '<%sd'%length
00187 start = end
00188 end += struct.calcsize(pattern)
00189 val1.joint_positions = struct.unpack(pattern, str[start:end])
00190 self.model_joints_states.append(val1)
00191 return self
00192 except struct.error as e:
00193 raise genpy.DeserializationError(e)
00194
00195
00196 def serialize_numpy(self, buff, numpy):
00197 """
00198 serialize message with numpy array types into buffer
00199 :param buff: buffer, ``StringIO``
00200 :param numpy: numpy python module
00201 """
00202 try:
00203 length = len(self.model_names)
00204 buff.write(_struct_I.pack(length))
00205 for val1 in self.model_names:
00206 length = len(val1)
00207 if python3 or type(val1) == unicode:
00208 val1 = val1.encode('utf-8')
00209 length = len(val1)
00210 buff.write(struct.pack('<I%ss'%length, length, val1))
00211 length = len(self.model_joints_states)
00212 buff.write(_struct_I.pack(length))
00213 for val1 in self.model_joints_states:
00214 length = len(val1.model_pose)
00215 buff.write(_struct_I.pack(length))
00216 for val2 in val1.model_pose:
00217 _v5 = val2.position
00218 _x = _v5
00219 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00220 _v6 = val2.orientation
00221 _x = _v6
00222 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00223 length = len(val1.joint_names)
00224 buff.write(_struct_I.pack(length))
00225 for val2 in val1.joint_names:
00226 length = len(val2)
00227 if python3 or type(val2) == unicode:
00228 val2 = val2.encode('utf-8')
00229 length = len(val2)
00230 buff.write(struct.pack('<I%ss'%length, length, val2))
00231 length = len(val1.joint_positions)
00232 buff.write(_struct_I.pack(length))
00233 pattern = '<%sd'%length
00234 buff.write(val1.joint_positions.tostring())
00235 except struct.error as se: self._check_types(se)
00236 except TypeError as te: self._check_types(te)
00237
00238 def deserialize_numpy(self, str, numpy):
00239 """
00240 unpack serialized message in str into this message instance using numpy for array types
00241 :param str: byte array of serialized message, ``str``
00242 :param numpy: numpy python module
00243 """
00244 try:
00245 if self.model_joints_states is None:
00246 self.model_joints_states = None
00247 end = 0
00248 start = end
00249 end += 4
00250 (length,) = _struct_I.unpack(str[start:end])
00251 self.model_names = []
00252 for i in range(0, length):
00253 start = end
00254 end += 4
00255 (length,) = _struct_I.unpack(str[start:end])
00256 start = end
00257 end += length
00258 if python3:
00259 val1 = str[start:end].decode('utf-8')
00260 else:
00261 val1 = str[start:end]
00262 self.model_names.append(val1)
00263 start = end
00264 end += 4
00265 (length,) = _struct_I.unpack(str[start:end])
00266 self.model_joints_states = []
00267 for i in range(0, length):
00268 val1 = pr2_gazebo_plugins.msg.ModelJointsState()
00269 start = end
00270 end += 4
00271 (length,) = _struct_I.unpack(str[start:end])
00272 val1.model_pose = []
00273 for i in range(0, length):
00274 val2 = geometry_msgs.msg.Pose()
00275 _v7 = val2.position
00276 _x = _v7
00277 start = end
00278 end += 24
00279 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00280 _v8 = val2.orientation
00281 _x = _v8
00282 start = end
00283 end += 32
00284 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00285 val1.model_pose.append(val2)
00286 start = end
00287 end += 4
00288 (length,) = _struct_I.unpack(str[start:end])
00289 val1.joint_names = []
00290 for i in range(0, length):
00291 start = end
00292 end += 4
00293 (length,) = _struct_I.unpack(str[start:end])
00294 start = end
00295 end += length
00296 if python3:
00297 val2 = str[start:end].decode('utf-8')
00298 else:
00299 val2 = str[start:end]
00300 val1.joint_names.append(val2)
00301 start = end
00302 end += 4
00303 (length,) = _struct_I.unpack(str[start:end])
00304 pattern = '<%sd'%length
00305 start = end
00306 end += struct.calcsize(pattern)
00307 val1.joint_positions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00308 self.model_joints_states.append(val1)
00309 return self
00310 except struct.error as e:
00311 raise genpy.DeserializationError(e)
00312
00313 _struct_I = genpy.struct_I
00314 _struct_4d = struct.Struct("<4d")
00315 _struct_3d = struct.Struct("<3d")
00316 """autogenerated by genpy from pr2_gazebo_plugins/SetModelsJointsStatesResponse.msg. Do not edit."""
00317 import sys
00318 python3 = True if sys.hexversion > 0x03000000 else False
00319 import genpy
00320 import struct
00321
00322
00323 class SetModelsJointsStatesResponse(genpy.Message):
00324 _md5sum = "2ec6f3eff0161f4257b808b12bc830c2"
00325 _type = "pr2_gazebo_plugins/SetModelsJointsStatesResponse"
00326 _has_header = False
00327 _full_text = """bool success
00328 string status_message
00329
00330
00331 """
00332 __slots__ = ['success','status_message']
00333 _slot_types = ['bool','string']
00334
00335 def __init__(self, *args, **kwds):
00336 """
00337 Constructor. Any message fields that are implicitly/explicitly
00338 set to None will be assigned a default value. The recommend
00339 use is keyword arguments as this is more robust to future message
00340 changes. You cannot mix in-order arguments and keyword arguments.
00341
00342 The available fields are:
00343 success,status_message
00344
00345 :param args: complete set of field values, in .msg order
00346 :param kwds: use keyword arguments corresponding to message field names
00347 to set specific fields.
00348 """
00349 if args or kwds:
00350 super(SetModelsJointsStatesResponse, self).__init__(*args, **kwds)
00351
00352 if self.success is None:
00353 self.success = False
00354 if self.status_message is None:
00355 self.status_message = ''
00356 else:
00357 self.success = False
00358 self.status_message = ''
00359
00360 def _get_types(self):
00361 """
00362 internal API method
00363 """
00364 return self._slot_types
00365
00366 def serialize(self, buff):
00367 """
00368 serialize message into buffer
00369 :param buff: buffer, ``StringIO``
00370 """
00371 try:
00372 buff.write(_struct_B.pack(self.success))
00373 _x = self.status_message
00374 length = len(_x)
00375 if python3 or type(_x) == unicode:
00376 _x = _x.encode('utf-8')
00377 length = len(_x)
00378 buff.write(struct.pack('<I%ss'%length, length, _x))
00379 except struct.error as se: self._check_types(se)
00380 except TypeError as te: self._check_types(te)
00381
00382 def deserialize(self, str):
00383 """
00384 unpack serialized message in str into this message instance
00385 :param str: byte array of serialized message, ``str``
00386 """
00387 try:
00388 end = 0
00389 start = end
00390 end += 1
00391 (self.success,) = _struct_B.unpack(str[start:end])
00392 self.success = bool(self.success)
00393 start = end
00394 end += 4
00395 (length,) = _struct_I.unpack(str[start:end])
00396 start = end
00397 end += length
00398 if python3:
00399 self.status_message = str[start:end].decode('utf-8')
00400 else:
00401 self.status_message = str[start:end]
00402 return self
00403 except struct.error as e:
00404 raise genpy.DeserializationError(e)
00405
00406
00407 def serialize_numpy(self, buff, numpy):
00408 """
00409 serialize message with numpy array types into buffer
00410 :param buff: buffer, ``StringIO``
00411 :param numpy: numpy python module
00412 """
00413 try:
00414 buff.write(_struct_B.pack(self.success))
00415 _x = self.status_message
00416 length = len(_x)
00417 if python3 or type(_x) == unicode:
00418 _x = _x.encode('utf-8')
00419 length = len(_x)
00420 buff.write(struct.pack('<I%ss'%length, length, _x))
00421 except struct.error as se: self._check_types(se)
00422 except TypeError as te: self._check_types(te)
00423
00424 def deserialize_numpy(self, str, numpy):
00425 """
00426 unpack serialized message in str into this message instance using numpy for array types
00427 :param str: byte array of serialized message, ``str``
00428 :param numpy: numpy python module
00429 """
00430 try:
00431 end = 0
00432 start = end
00433 end += 1
00434 (self.success,) = _struct_B.unpack(str[start:end])
00435 self.success = bool(self.success)
00436 start = end
00437 end += 4
00438 (length,) = _struct_I.unpack(str[start:end])
00439 start = end
00440 end += length
00441 if python3:
00442 self.status_message = str[start:end].decode('utf-8')
00443 else:
00444 self.status_message = str[start:end]
00445 return self
00446 except struct.error as e:
00447 raise genpy.DeserializationError(e)
00448
00449 _struct_I = genpy.struct_I
00450 _struct_B = struct.Struct("<B")
00451 class SetModelsJointsStates(object):
00452 _type = 'pr2_gazebo_plugins/SetModelsJointsStates'
00453 _md5sum = 'b3f4760ee77e28f605915bcee447b72d'
00454 _request_class = SetModelsJointsStatesRequest
00455 _response_class = SetModelsJointsStatesResponse