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