_SetModelPriorSrv.py
Go to the documentation of this file.
00001 """autogenerated by genpy from articulation_msgs/SetModelPriorSrvRequest.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 sensor_msgs.msg
00008 import geometry_msgs.msg
00009 import articulation_msgs.msg
00010 import std_msgs.msg
00011 
00012 class SetModelPriorSrvRequest(genpy.Message):
00013   _md5sum = "492b025b4d335f83e3fab65eb3211a27"
00014   _type = "articulation_msgs/SetModelPriorSrvRequest"
00015   _has_header = False #flag to mark the presence of a Header object
00016   _full_text = """
00017 
00018 
00019 
00020 
00021 
00022 articulation_msgs/ModelMsg[] model
00023 
00024 ================================================================================
00025 MSG: articulation_msgs/ModelMsg
00026 # Single kinematic model
00027 #
00028 # A kinematic model is defined by its model class name, and a set of parameters. 
00029 # The client may additionally specify a model id, that can be used to colorize the
00030 # model when visualized using the RVIZ model display.
00031 # 
00032 # For a list of currently implemented models, see the documetation at
00033 # http://www.ros.org/wiki/articulation_models
00034 #
00035 #
00036 
00037 std_msgs/Header header                        # frame and timestamp
00038 
00039 int32 id                             # user specified model id
00040 string name                          # name of the model family (e.g. "rotational",
00041                                      # "prismatic", "pca-gp", "rigid")
00042 articulation_msgs/ParamMsg[] params  # model parameters
00043 articulation_msgs/TrackMsg track     # trajectory from which the model is estimated, or
00044                                      # that is evaluated using the model
00045 
00046 ================================================================================
00047 MSG: std_msgs/Header
00048 # Standard metadata for higher-level stamped data types.
00049 # This is generally used to communicate timestamped data 
00050 # in a particular coordinate frame.
00051 # 
00052 # sequence ID: consecutively increasing ID 
00053 uint32 seq
00054 #Two-integer timestamp that is expressed as:
00055 # * stamp.secs: seconds (stamp_secs) since epoch
00056 # * stamp.nsecs: nanoseconds since stamp_secs
00057 # time-handling sugar is provided by the client library
00058 time stamp
00059 #Frame this data is associated with
00060 # 0: no frame
00061 # 1: global frame
00062 string frame_id
00063 
00064 ================================================================================
00065 MSG: articulation_msgs/ParamMsg
00066 # Single parameter passed to or from model fitting
00067 #
00068 # This mechanism allows to flexibly pass parameters to 
00069 # model fitting (and vice versa). Note that these parameters 
00070 # are model-specific: A client may supply additional
00071 # parameters to the model estimator, and, similarly, a estimator
00072 # may add the estimated model parameters to the model message.
00073 # When the model is then evaluated, for example to make predictions
00074 # or to compute the likelihood, the model class can then use
00075 # these parameters.
00076 #
00077 # A parameter has a name, a value, and a type. The type globally
00078 # indicates whether it is a prior parameter (prior to model fitting),
00079 # or a model parameter (found during model fitting, using a maximum-
00080 # likelihood estimator), or a cached evaluation (e.g., the likelihood
00081 # or the BIC are a typical "side"-product of model estimation, and
00082 # can therefore already be cached).
00083 #
00084 # For a list of currently used parameters, see the documentation at
00085 # http://www.ros.org/wiki/articulation_models
00086 #
00087 
00088 uint8 PRIOR=0   # indicates a prior model parameter 
00089                 # (e.g., "sigma_position")
00090 uint8 PARAM=1   # indicates a estimated model parameter 
00091                 # (e.g., "rot_radius", the estimated radius)
00092 uint8 EVAL=2    # indicates a cached evaluation of the model, given 
00093                 # the current trajectory
00094                 # (e.g., "loglikelihood", the log likelihood of the
00095                 # data, given the model and its parameters)
00096 
00097 string name     # name of the parameter
00098 float64 value   # value of the parameter
00099 uint8 type      # type of the parameter (PRIOR, PARAM, EVAL)
00100 
00101 
00102 ================================================================================
00103 MSG: articulation_msgs/TrackMsg
00104 # Single kinematic trajectory
00105 #
00106 # This message contains a kinematic trajectory. The trajectory is specified
00107 # as a vector of 6D poses. An additional flag, track_type, indicates whether
00108 # the track is valid, and whether it includes orientation. The track id
00109 # can be used for automatic coloring in the RVIZ track plugin, and can be 
00110 # freely chosen by the client. 
00111 #
00112 # A model is fitting only from the trajectory stored in the pose[]-vector. 
00113 # Additional information may be associated to each pose using the channels
00114 # vector, with arbitrary # fields (e.g., to include applied/measured forces). 
00115 #
00116 # After model evaluation,
00117 # also the associated configurations of the object are stored in the channels,
00118 # named "q[0]".."q[DOF-1]", where DOF is the number of degrees of freedom.
00119 # Model evaluation also projects the poses in the pose vector onto the model,
00120 # and stores these ideal poses in the vector pose_projected. Further, during model
00121 # evaluation, a new set of (uniform) configurations over the valid configuration
00122 # range is sampled, and the result is stored in pose_resampled.
00123 # The vector pose_flags contains additional display flags for the poses in the
00124 # pose vector, for example, whether a pose is visible and/or
00125 # the end of a trajectory segment. At the moment, this is only used by the
00126 # prior_model_learner.
00127 #
00128 
00129 std_msgs/Header header                        # frame and timestamp
00130 int32 id                                # used-specified track id
00131 
00132 geometry_msgs/Pose[] pose               # sequence of poses, defining the observed trajectory
00133 std_msgs/Header[] pose_headers                   # Timestamp and frame for each pose (and pose_projected)
00134 geometry_msgs/Pose[] pose_projected     # sequence of poses, projected to the model 
00135                                         # (after model evaluation)
00136 geometry_msgs/Pose[] pose_resampled     # sequence of poses, re-sampled from the model in
00137                                         # the valid configuration range
00138 uint32[] pose_flags                     # bit-wise combination of POSE_VISIBLE and POSE_END_OF_SEGMENT
00139 
00140 uint32 POSE_VISIBLE=1
00141 uint32 POSE_END_OF_SEGMENT=2
00142 
00143 # Each channel should have the same number of elements as pose array, 
00144 # and the data in each channel should correspond 1:1 with each pose
00145 # possible channels: "width", "height", "rgb", ...
00146 sensor_msgs/ChannelFloat32[] channels       
00147 
00148 
00149 
00150 ================================================================================
00151 MSG: geometry_msgs/Pose
00152 # A representation of pose in free space, composed of postion and orientation. 
00153 Point position
00154 Quaternion orientation
00155 
00156 ================================================================================
00157 MSG: geometry_msgs/Point
00158 # This contains the position of a point in free space
00159 float64 x
00160 float64 y
00161 float64 z
00162 
00163 ================================================================================
00164 MSG: geometry_msgs/Quaternion
00165 # This represents an orientation in free space in quaternion form.
00166 
00167 float64 x
00168 float64 y
00169 float64 z
00170 float64 w
00171 
00172 ================================================================================
00173 MSG: sensor_msgs/ChannelFloat32
00174 # This message is used by the PointCloud message to hold optional data
00175 # associated with each point in the cloud. The length of the values
00176 # array should be the same as the length of the points array in the
00177 # PointCloud, and each value should be associated with the corresponding
00178 # point.
00179 
00180 # Channel names in existing practice include:
00181 #   "u", "v" - row and column (respectively) in the left stereo image.
00182 #              This is opposite to usual conventions but remains for
00183 #              historical reasons. The newer PointCloud2 message has no
00184 #              such problem.
00185 #   "rgb" - For point clouds produced by color stereo cameras. uint8
00186 #           (R,G,B) values packed into the least significant 24 bits,
00187 #           in order.
00188 #   "intensity" - laser or pixel intensity.
00189 #   "distance"
00190 
00191 # The channel name should give semantics of the channel (e.g.
00192 # "intensity" instead of "value").
00193 string name
00194 
00195 # The values array should be 1-1 with the elements of the associated
00196 # PointCloud.
00197 float32[] values
00198 
00199 """
00200   __slots__ = ['model']
00201   _slot_types = ['articulation_msgs/ModelMsg[]']
00202 
00203   def __init__(self, *args, **kwds):
00204     """
00205     Constructor. Any message fields that are implicitly/explicitly
00206     set to None will be assigned a default value. The recommend
00207     use is keyword arguments as this is more robust to future message
00208     changes.  You cannot mix in-order arguments and keyword arguments.
00209 
00210     The available fields are:
00211        model
00212 
00213     :param args: complete set of field values, in .msg order
00214     :param kwds: use keyword arguments corresponding to message field names
00215     to set specific fields.
00216     """
00217     if args or kwds:
00218       super(SetModelPriorSrvRequest, self).__init__(*args, **kwds)
00219       #message fields cannot be None, assign default values for those that are
00220       if self.model is None:
00221         self.model = []
00222     else:
00223       self.model = []
00224 
00225   def _get_types(self):
00226     """
00227     internal API method
00228     """
00229     return self._slot_types
00230 
00231   def serialize(self, buff):
00232     """
00233     serialize message into buffer
00234     :param buff: buffer, ``StringIO``
00235     """
00236     try:
00237       length = len(self.model)
00238       buff.write(_struct_I.pack(length))
00239       for val1 in self.model:
00240         _v1 = val1.header
00241         buff.write(_struct_I.pack(_v1.seq))
00242         _v2 = _v1.stamp
00243         _x = _v2
00244         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00245         _x = _v1.frame_id
00246         length = len(_x)
00247         if python3 or type(_x) == unicode:
00248           _x = _x.encode('utf-8')
00249           length = len(_x)
00250         buff.write(struct.pack('<I%ss'%length, length, _x))
00251         buff.write(_struct_i.pack(val1.id))
00252         _x = val1.name
00253         length = len(_x)
00254         if python3 or type(_x) == unicode:
00255           _x = _x.encode('utf-8')
00256           length = len(_x)
00257         buff.write(struct.pack('<I%ss'%length, length, _x))
00258         length = len(val1.params)
00259         buff.write(_struct_I.pack(length))
00260         for val2 in val1.params:
00261           _x = val2.name
00262           length = len(_x)
00263           if python3 or type(_x) == unicode:
00264             _x = _x.encode('utf-8')
00265             length = len(_x)
00266           buff.write(struct.pack('<I%ss'%length, length, _x))
00267           _x = val2
00268           buff.write(_struct_dB.pack(_x.value, _x.type))
00269         _v3 = val1.track
00270         _v4 = _v3.header
00271         buff.write(_struct_I.pack(_v4.seq))
00272         _v5 = _v4.stamp
00273         _x = _v5
00274         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00275         _x = _v4.frame_id
00276         length = len(_x)
00277         if python3 or type(_x) == unicode:
00278           _x = _x.encode('utf-8')
00279           length = len(_x)
00280         buff.write(struct.pack('<I%ss'%length, length, _x))
00281         buff.write(_struct_i.pack(_v3.id))
00282         length = len(_v3.pose)
00283         buff.write(_struct_I.pack(length))
00284         for val3 in _v3.pose:
00285           _v6 = val3.position
00286           _x = _v6
00287           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00288           _v7 = val3.orientation
00289           _x = _v7
00290           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00291         length = len(_v3.pose_headers)
00292         buff.write(_struct_I.pack(length))
00293         for val3 in _v3.pose_headers:
00294           buff.write(_struct_I.pack(val3.seq))
00295           _v8 = val3.stamp
00296           _x = _v8
00297           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00298           _x = val3.frame_id
00299           length = len(_x)
00300           if python3 or type(_x) == unicode:
00301             _x = _x.encode('utf-8')
00302             length = len(_x)
00303           buff.write(struct.pack('<I%ss'%length, length, _x))
00304         length = len(_v3.pose_projected)
00305         buff.write(_struct_I.pack(length))
00306         for val3 in _v3.pose_projected:
00307           _v9 = val3.position
00308           _x = _v9
00309           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00310           _v10 = val3.orientation
00311           _x = _v10
00312           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00313         length = len(_v3.pose_resampled)
00314         buff.write(_struct_I.pack(length))
00315         for val3 in _v3.pose_resampled:
00316           _v11 = val3.position
00317           _x = _v11
00318           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00319           _v12 = val3.orientation
00320           _x = _v12
00321           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00322         length = len(_v3.pose_flags)
00323         buff.write(_struct_I.pack(length))
00324         pattern = '<%sI'%length
00325         buff.write(struct.pack(pattern, *_v3.pose_flags))
00326         length = len(_v3.channels)
00327         buff.write(_struct_I.pack(length))
00328         for val3 in _v3.channels:
00329           _x = val3.name
00330           length = len(_x)
00331           if python3 or type(_x) == unicode:
00332             _x = _x.encode('utf-8')
00333             length = len(_x)
00334           buff.write(struct.pack('<I%ss'%length, length, _x))
00335           length = len(val3.values)
00336           buff.write(_struct_I.pack(length))
00337           pattern = '<%sf'%length
00338           buff.write(struct.pack(pattern, *val3.values))
00339     except struct.error as se: self._check_types(se)
00340     except TypeError as te: self._check_types(te)
00341 
00342   def deserialize(self, str):
00343     """
00344     unpack serialized message in str into this message instance
00345     :param str: byte array of serialized message, ``str``
00346     """
00347     try:
00348       if self.model is None:
00349         self.model = None
00350       end = 0
00351       start = end
00352       end += 4
00353       (length,) = _struct_I.unpack(str[start:end])
00354       self.model = []
00355       for i in range(0, length):
00356         val1 = articulation_msgs.msg.ModelMsg()
00357         _v13 = val1.header
00358         start = end
00359         end += 4
00360         (_v13.seq,) = _struct_I.unpack(str[start:end])
00361         _v14 = _v13.stamp
00362         _x = _v14
00363         start = end
00364         end += 8
00365         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00366         start = end
00367         end += 4
00368         (length,) = _struct_I.unpack(str[start:end])
00369         start = end
00370         end += length
00371         if python3:
00372           _v13.frame_id = str[start:end].decode('utf-8')
00373         else:
00374           _v13.frame_id = str[start:end]
00375         start = end
00376         end += 4
00377         (val1.id,) = _struct_i.unpack(str[start:end])
00378         start = end
00379         end += 4
00380         (length,) = _struct_I.unpack(str[start:end])
00381         start = end
00382         end += length
00383         if python3:
00384           val1.name = str[start:end].decode('utf-8')
00385         else:
00386           val1.name = str[start:end]
00387         start = end
00388         end += 4
00389         (length,) = _struct_I.unpack(str[start:end])
00390         val1.params = []
00391         for i in range(0, length):
00392           val2 = articulation_msgs.msg.ParamMsg()
00393           start = end
00394           end += 4
00395           (length,) = _struct_I.unpack(str[start:end])
00396           start = end
00397           end += length
00398           if python3:
00399             val2.name = str[start:end].decode('utf-8')
00400           else:
00401             val2.name = str[start:end]
00402           _x = val2
00403           start = end
00404           end += 9
00405           (_x.value, _x.type,) = _struct_dB.unpack(str[start:end])
00406           val1.params.append(val2)
00407         _v15 = val1.track
00408         _v16 = _v15.header
00409         start = end
00410         end += 4
00411         (_v16.seq,) = _struct_I.unpack(str[start:end])
00412         _v17 = _v16.stamp
00413         _x = _v17
00414         start = end
00415         end += 8
00416         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00417         start = end
00418         end += 4
00419         (length,) = _struct_I.unpack(str[start:end])
00420         start = end
00421         end += length
00422         if python3:
00423           _v16.frame_id = str[start:end].decode('utf-8')
00424         else:
00425           _v16.frame_id = str[start:end]
00426         start = end
00427         end += 4
00428         (_v15.id,) = _struct_i.unpack(str[start:end])
00429         start = end
00430         end += 4
00431         (length,) = _struct_I.unpack(str[start:end])
00432         _v15.pose = []
00433         for i in range(0, length):
00434           val3 = geometry_msgs.msg.Pose()
00435           _v18 = val3.position
00436           _x = _v18
00437           start = end
00438           end += 24
00439           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00440           _v19 = val3.orientation
00441           _x = _v19
00442           start = end
00443           end += 32
00444           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00445           _v15.pose.append(val3)
00446         start = end
00447         end += 4
00448         (length,) = _struct_I.unpack(str[start:end])
00449         _v15.pose_headers = []
00450         for i in range(0, length):
00451           val3 = std_msgs.msg.Header()
00452           start = end
00453           end += 4
00454           (val3.seq,) = _struct_I.unpack(str[start:end])
00455           _v20 = val3.stamp
00456           _x = _v20
00457           start = end
00458           end += 8
00459           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00460           start = end
00461           end += 4
00462           (length,) = _struct_I.unpack(str[start:end])
00463           start = end
00464           end += length
00465           if python3:
00466             val3.frame_id = str[start:end].decode('utf-8')
00467           else:
00468             val3.frame_id = str[start:end]
00469           _v15.pose_headers.append(val3)
00470         start = end
00471         end += 4
00472         (length,) = _struct_I.unpack(str[start:end])
00473         _v15.pose_projected = []
00474         for i in range(0, length):
00475           val3 = geometry_msgs.msg.Pose()
00476           _v21 = val3.position
00477           _x = _v21
00478           start = end
00479           end += 24
00480           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00481           _v22 = val3.orientation
00482           _x = _v22
00483           start = end
00484           end += 32
00485           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00486           _v15.pose_projected.append(val3)
00487         start = end
00488         end += 4
00489         (length,) = _struct_I.unpack(str[start:end])
00490         _v15.pose_resampled = []
00491         for i in range(0, length):
00492           val3 = geometry_msgs.msg.Pose()
00493           _v23 = val3.position
00494           _x = _v23
00495           start = end
00496           end += 24
00497           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00498           _v24 = val3.orientation
00499           _x = _v24
00500           start = end
00501           end += 32
00502           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00503           _v15.pose_resampled.append(val3)
00504         start = end
00505         end += 4
00506         (length,) = _struct_I.unpack(str[start:end])
00507         pattern = '<%sI'%length
00508         start = end
00509         end += struct.calcsize(pattern)
00510         _v15.pose_flags = struct.unpack(pattern, str[start:end])
00511         start = end
00512         end += 4
00513         (length,) = _struct_I.unpack(str[start:end])
00514         _v15.channels = []
00515         for i in range(0, length):
00516           val3 = sensor_msgs.msg.ChannelFloat32()
00517           start = end
00518           end += 4
00519           (length,) = _struct_I.unpack(str[start:end])
00520           start = end
00521           end += length
00522           if python3:
00523             val3.name = str[start:end].decode('utf-8')
00524           else:
00525             val3.name = str[start:end]
00526           start = end
00527           end += 4
00528           (length,) = _struct_I.unpack(str[start:end])
00529           pattern = '<%sf'%length
00530           start = end
00531           end += struct.calcsize(pattern)
00532           val3.values = struct.unpack(pattern, str[start:end])
00533           _v15.channels.append(val3)
00534         self.model.append(val1)
00535       return self
00536     except struct.error as e:
00537       raise genpy.DeserializationError(e) #most likely buffer underfill
00538 
00539 
00540   def serialize_numpy(self, buff, numpy):
00541     """
00542     serialize message with numpy array types into buffer
00543     :param buff: buffer, ``StringIO``
00544     :param numpy: numpy python module
00545     """
00546     try:
00547       length = len(self.model)
00548       buff.write(_struct_I.pack(length))
00549       for val1 in self.model:
00550         _v25 = val1.header
00551         buff.write(_struct_I.pack(_v25.seq))
00552         _v26 = _v25.stamp
00553         _x = _v26
00554         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00555         _x = _v25.frame_id
00556         length = len(_x)
00557         if python3 or type(_x) == unicode:
00558           _x = _x.encode('utf-8')
00559           length = len(_x)
00560         buff.write(struct.pack('<I%ss'%length, length, _x))
00561         buff.write(_struct_i.pack(val1.id))
00562         _x = val1.name
00563         length = len(_x)
00564         if python3 or type(_x) == unicode:
00565           _x = _x.encode('utf-8')
00566           length = len(_x)
00567         buff.write(struct.pack('<I%ss'%length, length, _x))
00568         length = len(val1.params)
00569         buff.write(_struct_I.pack(length))
00570         for val2 in val1.params:
00571           _x = val2.name
00572           length = len(_x)
00573           if python3 or type(_x) == unicode:
00574             _x = _x.encode('utf-8')
00575             length = len(_x)
00576           buff.write(struct.pack('<I%ss'%length, length, _x))
00577           _x = val2
00578           buff.write(_struct_dB.pack(_x.value, _x.type))
00579         _v27 = val1.track
00580         _v28 = _v27.header
00581         buff.write(_struct_I.pack(_v28.seq))
00582         _v29 = _v28.stamp
00583         _x = _v29
00584         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00585         _x = _v28.frame_id
00586         length = len(_x)
00587         if python3 or type(_x) == unicode:
00588           _x = _x.encode('utf-8')
00589           length = len(_x)
00590         buff.write(struct.pack('<I%ss'%length, length, _x))
00591         buff.write(_struct_i.pack(_v27.id))
00592         length = len(_v27.pose)
00593         buff.write(_struct_I.pack(length))
00594         for val3 in _v27.pose:
00595           _v30 = val3.position
00596           _x = _v30
00597           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00598           _v31 = val3.orientation
00599           _x = _v31
00600           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00601         length = len(_v27.pose_headers)
00602         buff.write(_struct_I.pack(length))
00603         for val3 in _v27.pose_headers:
00604           buff.write(_struct_I.pack(val3.seq))
00605           _v32 = val3.stamp
00606           _x = _v32
00607           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00608           _x = val3.frame_id
00609           length = len(_x)
00610           if python3 or type(_x) == unicode:
00611             _x = _x.encode('utf-8')
00612             length = len(_x)
00613           buff.write(struct.pack('<I%ss'%length, length, _x))
00614         length = len(_v27.pose_projected)
00615         buff.write(_struct_I.pack(length))
00616         for val3 in _v27.pose_projected:
00617           _v33 = val3.position
00618           _x = _v33
00619           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00620           _v34 = val3.orientation
00621           _x = _v34
00622           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00623         length = len(_v27.pose_resampled)
00624         buff.write(_struct_I.pack(length))
00625         for val3 in _v27.pose_resampled:
00626           _v35 = val3.position
00627           _x = _v35
00628           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00629           _v36 = val3.orientation
00630           _x = _v36
00631           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00632         length = len(_v27.pose_flags)
00633         buff.write(_struct_I.pack(length))
00634         pattern = '<%sI'%length
00635         buff.write(_v27.pose_flags.tostring())
00636         length = len(_v27.channels)
00637         buff.write(_struct_I.pack(length))
00638         for val3 in _v27.channels:
00639           _x = val3.name
00640           length = len(_x)
00641           if python3 or type(_x) == unicode:
00642             _x = _x.encode('utf-8')
00643             length = len(_x)
00644           buff.write(struct.pack('<I%ss'%length, length, _x))
00645           length = len(val3.values)
00646           buff.write(_struct_I.pack(length))
00647           pattern = '<%sf'%length
00648           buff.write(val3.values.tostring())
00649     except struct.error as se: self._check_types(se)
00650     except TypeError as te: self._check_types(te)
00651 
00652   def deserialize_numpy(self, str, numpy):
00653     """
00654     unpack serialized message in str into this message instance using numpy for array types
00655     :param str: byte array of serialized message, ``str``
00656     :param numpy: numpy python module
00657     """
00658     try:
00659       if self.model is None:
00660         self.model = None
00661       end = 0
00662       start = end
00663       end += 4
00664       (length,) = _struct_I.unpack(str[start:end])
00665       self.model = []
00666       for i in range(0, length):
00667         val1 = articulation_msgs.msg.ModelMsg()
00668         _v37 = val1.header
00669         start = end
00670         end += 4
00671         (_v37.seq,) = _struct_I.unpack(str[start:end])
00672         _v38 = _v37.stamp
00673         _x = _v38
00674         start = end
00675         end += 8
00676         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00677         start = end
00678         end += 4
00679         (length,) = _struct_I.unpack(str[start:end])
00680         start = end
00681         end += length
00682         if python3:
00683           _v37.frame_id = str[start:end].decode('utf-8')
00684         else:
00685           _v37.frame_id = str[start:end]
00686         start = end
00687         end += 4
00688         (val1.id,) = _struct_i.unpack(str[start:end])
00689         start = end
00690         end += 4
00691         (length,) = _struct_I.unpack(str[start:end])
00692         start = end
00693         end += length
00694         if python3:
00695           val1.name = str[start:end].decode('utf-8')
00696         else:
00697           val1.name = str[start:end]
00698         start = end
00699         end += 4
00700         (length,) = _struct_I.unpack(str[start:end])
00701         val1.params = []
00702         for i in range(0, length):
00703           val2 = articulation_msgs.msg.ParamMsg()
00704           start = end
00705           end += 4
00706           (length,) = _struct_I.unpack(str[start:end])
00707           start = end
00708           end += length
00709           if python3:
00710             val2.name = str[start:end].decode('utf-8')
00711           else:
00712             val2.name = str[start:end]
00713           _x = val2
00714           start = end
00715           end += 9
00716           (_x.value, _x.type,) = _struct_dB.unpack(str[start:end])
00717           val1.params.append(val2)
00718         _v39 = val1.track
00719         _v40 = _v39.header
00720         start = end
00721         end += 4
00722         (_v40.seq,) = _struct_I.unpack(str[start:end])
00723         _v41 = _v40.stamp
00724         _x = _v41
00725         start = end
00726         end += 8
00727         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00728         start = end
00729         end += 4
00730         (length,) = _struct_I.unpack(str[start:end])
00731         start = end
00732         end += length
00733         if python3:
00734           _v40.frame_id = str[start:end].decode('utf-8')
00735         else:
00736           _v40.frame_id = str[start:end]
00737         start = end
00738         end += 4
00739         (_v39.id,) = _struct_i.unpack(str[start:end])
00740         start = end
00741         end += 4
00742         (length,) = _struct_I.unpack(str[start:end])
00743         _v39.pose = []
00744         for i in range(0, length):
00745           val3 = geometry_msgs.msg.Pose()
00746           _v42 = val3.position
00747           _x = _v42
00748           start = end
00749           end += 24
00750           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00751           _v43 = val3.orientation
00752           _x = _v43
00753           start = end
00754           end += 32
00755           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00756           _v39.pose.append(val3)
00757         start = end
00758         end += 4
00759         (length,) = _struct_I.unpack(str[start:end])
00760         _v39.pose_headers = []
00761         for i in range(0, length):
00762           val3 = std_msgs.msg.Header()
00763           start = end
00764           end += 4
00765           (val3.seq,) = _struct_I.unpack(str[start:end])
00766           _v44 = val3.stamp
00767           _x = _v44
00768           start = end
00769           end += 8
00770           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00771           start = end
00772           end += 4
00773           (length,) = _struct_I.unpack(str[start:end])
00774           start = end
00775           end += length
00776           if python3:
00777             val3.frame_id = str[start:end].decode('utf-8')
00778           else:
00779             val3.frame_id = str[start:end]
00780           _v39.pose_headers.append(val3)
00781         start = end
00782         end += 4
00783         (length,) = _struct_I.unpack(str[start:end])
00784         _v39.pose_projected = []
00785         for i in range(0, length):
00786           val3 = geometry_msgs.msg.Pose()
00787           _v45 = val3.position
00788           _x = _v45
00789           start = end
00790           end += 24
00791           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00792           _v46 = val3.orientation
00793           _x = _v46
00794           start = end
00795           end += 32
00796           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00797           _v39.pose_projected.append(val3)
00798         start = end
00799         end += 4
00800         (length,) = _struct_I.unpack(str[start:end])
00801         _v39.pose_resampled = []
00802         for i in range(0, length):
00803           val3 = geometry_msgs.msg.Pose()
00804           _v47 = val3.position
00805           _x = _v47
00806           start = end
00807           end += 24
00808           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00809           _v48 = val3.orientation
00810           _x = _v48
00811           start = end
00812           end += 32
00813           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00814           _v39.pose_resampled.append(val3)
00815         start = end
00816         end += 4
00817         (length,) = _struct_I.unpack(str[start:end])
00818         pattern = '<%sI'%length
00819         start = end
00820         end += struct.calcsize(pattern)
00821         _v39.pose_flags = numpy.frombuffer(str[start:end], dtype=numpy.uint32, count=length)
00822         start = end
00823         end += 4
00824         (length,) = _struct_I.unpack(str[start:end])
00825         _v39.channels = []
00826         for i in range(0, length):
00827           val3 = sensor_msgs.msg.ChannelFloat32()
00828           start = end
00829           end += 4
00830           (length,) = _struct_I.unpack(str[start:end])
00831           start = end
00832           end += length
00833           if python3:
00834             val3.name = str[start:end].decode('utf-8')
00835           else:
00836             val3.name = str[start:end]
00837           start = end
00838           end += 4
00839           (length,) = _struct_I.unpack(str[start:end])
00840           pattern = '<%sf'%length
00841           start = end
00842           end += struct.calcsize(pattern)
00843           val3.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00844           _v39.channels.append(val3)
00845         self.model.append(val1)
00846       return self
00847     except struct.error as e:
00848       raise genpy.DeserializationError(e) #most likely buffer underfill
00849 
00850 _struct_I = genpy.struct_I
00851 _struct_dB = struct.Struct("<dB")
00852 _struct_i = struct.Struct("<i")
00853 _struct_4d = struct.Struct("<4d")
00854 _struct_2I = struct.Struct("<2I")
00855 _struct_3d = struct.Struct("<3d")
00856 """autogenerated by genpy from articulation_msgs/SetModelPriorSrvResponse.msg. Do not edit."""
00857 import sys
00858 python3 = True if sys.hexversion > 0x03000000 else False
00859 import genpy
00860 import struct
00861 
00862 
00863 class SetModelPriorSrvResponse(genpy.Message):
00864   _md5sum = "d41d8cd98f00b204e9800998ecf8427e"
00865   _type = "articulation_msgs/SetModelPriorSrvResponse"
00866   _has_header = False #flag to mark the presence of a Header object
00867   _full_text = """
00868 
00869 
00870 """
00871   __slots__ = []
00872   _slot_types = []
00873 
00874   def __init__(self, *args, **kwds):
00875     """
00876     Constructor. Any message fields that are implicitly/explicitly
00877     set to None will be assigned a default value. The recommend
00878     use is keyword arguments as this is more robust to future message
00879     changes.  You cannot mix in-order arguments and keyword arguments.
00880 
00881     The available fields are:
00882        
00883 
00884     :param args: complete set of field values, in .msg order
00885     :param kwds: use keyword arguments corresponding to message field names
00886     to set specific fields.
00887     """
00888     if args or kwds:
00889       super(SetModelPriorSrvResponse, self).__init__(*args, **kwds)
00890 
00891   def _get_types(self):
00892     """
00893     internal API method
00894     """
00895     return self._slot_types
00896 
00897   def serialize(self, buff):
00898     """
00899     serialize message into buffer
00900     :param buff: buffer, ``StringIO``
00901     """
00902     try:
00903       pass
00904     except struct.error as se: self._check_types(se)
00905     except TypeError as te: self._check_types(te)
00906 
00907   def deserialize(self, str):
00908     """
00909     unpack serialized message in str into this message instance
00910     :param str: byte array of serialized message, ``str``
00911     """
00912     try:
00913       end = 0
00914       return self
00915     except struct.error as e:
00916       raise genpy.DeserializationError(e) #most likely buffer underfill
00917 
00918 
00919   def serialize_numpy(self, buff, numpy):
00920     """
00921     serialize message with numpy array types into buffer
00922     :param buff: buffer, ``StringIO``
00923     :param numpy: numpy python module
00924     """
00925     try:
00926       pass
00927     except struct.error as se: self._check_types(se)
00928     except TypeError as te: self._check_types(te)
00929 
00930   def deserialize_numpy(self, str, numpy):
00931     """
00932     unpack serialized message in str into this message instance using numpy for array types
00933     :param str: byte array of serialized message, ``str``
00934     :param numpy: numpy python module
00935     """
00936     try:
00937       end = 0
00938       return self
00939     except struct.error as e:
00940       raise genpy.DeserializationError(e) #most likely buffer underfill
00941 
00942 _struct_I = genpy.struct_I
00943 class SetModelPriorSrv(object):
00944   _type          = 'articulation_msgs/SetModelPriorSrv'
00945   _md5sum = '492b025b4d335f83e3fab65eb3211a27'
00946   _request_class  = SetModelPriorSrvRequest
00947   _response_class = SetModelPriorSrvResponse
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends


articulation_msgs
Author(s): Juergen Sturm
autogenerated on Wed Dec 26 2012 15:30:49