_ArticulatedObjectSrv.py
Go to the documentation of this file.
00001 """autogenerated by genpy from articulation_msgs/ArticulatedObjectSrvRequest.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 visualization_msgs.msg
00008 import articulation_msgs.msg
00009 import geometry_msgs.msg
00010 import sensor_msgs.msg
00011 import genpy
00012 import std_msgs.msg
00013 
00014 class ArticulatedObjectSrvRequest(genpy.Message):
00015   _md5sum = "5d5d9e6b857e5dae46feed46b9a03103"
00016   _type = "articulation_msgs/ArticulatedObjectSrvRequest"
00017   _has_header = False #flag to mark the presence of a Header object
00018   _full_text = """
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 articulation_msgs/ArticulatedObjectMsg object
00028 
00029 
00030 ================================================================================
00031 MSG: articulation_msgs/ArticulatedObjectMsg
00032 std_msgs/Header header
00033 
00034 articulation_msgs/TrackMsg[] parts    # observed trajectories for each object part 
00035 articulation_msgs/ParamMsg[] params   # global parameters
00036 articulation_msgs/ModelMsg[] models       # models, describing relationships between parts
00037 visualization_msgs/MarkerArray markers # marker visualization of models/object 
00038 
00039 ================================================================================
00040 MSG: std_msgs/Header
00041 # Standard metadata for higher-level stamped data types.
00042 # This is generally used to communicate timestamped data 
00043 # in a particular coordinate frame.
00044 # 
00045 # sequence ID: consecutively increasing ID 
00046 uint32 seq
00047 #Two-integer timestamp that is expressed as:
00048 # * stamp.secs: seconds (stamp_secs) since epoch
00049 # * stamp.nsecs: nanoseconds since stamp_secs
00050 # time-handling sugar is provided by the client library
00051 time stamp
00052 #Frame this data is associated with
00053 # 0: no frame
00054 # 1: global frame
00055 string frame_id
00056 
00057 ================================================================================
00058 MSG: articulation_msgs/TrackMsg
00059 # Single kinematic trajectory
00060 #
00061 # This message contains a kinematic trajectory. The trajectory is specified
00062 # as a vector of 6D poses. An additional flag, track_type, indicates whether
00063 # the track is valid, and whether it includes orientation. The track id
00064 # can be used for automatic coloring in the RVIZ track plugin, and can be 
00065 # freely chosen by the client. 
00066 #
00067 # A model is fitting only from the trajectory stored in the pose[]-vector. 
00068 # Additional information may be associated to each pose using the channels
00069 # vector, with arbitrary # fields (e.g., to include applied/measured forces). 
00070 #
00071 # After model evaluation,
00072 # also the associated configurations of the object are stored in the channels,
00073 # named "q[0]".."q[DOF-1]", where DOF is the number of degrees of freedom.
00074 # Model evaluation also projects the poses in the pose vector onto the model,
00075 # and stores these ideal poses in the vector pose_projected. Further, during model
00076 # evaluation, a new set of (uniform) configurations over the valid configuration
00077 # range is sampled, and the result is stored in pose_resampled.
00078 # The vector pose_flags contains additional display flags for the poses in the
00079 # pose vector, for example, whether a pose is visible and/or
00080 # the end of a trajectory segment. At the moment, this is only used by the
00081 # prior_model_learner.
00082 #
00083 
00084 std_msgs/Header header                        # frame and timestamp
00085 int32 id                                # used-specified track id
00086 
00087 geometry_msgs/Pose[] pose               # sequence of poses, defining the observed trajectory
00088 std_msgs/Header[] pose_headers                   # Timestamp and frame for each pose (and pose_projected)
00089 geometry_msgs/Pose[] pose_projected     # sequence of poses, projected to the model 
00090                                         # (after model evaluation)
00091 geometry_msgs/Pose[] pose_resampled     # sequence of poses, re-sampled from the model in
00092                                         # the valid configuration range
00093 uint32[] pose_flags                     # bit-wise combination of POSE_VISIBLE and POSE_END_OF_SEGMENT
00094 
00095 uint32 POSE_VISIBLE=1
00096 uint32 POSE_END_OF_SEGMENT=2
00097 
00098 # Each channel should have the same number of elements as pose array, 
00099 # and the data in each channel should correspond 1:1 with each pose
00100 # possible channels: "width", "height", "rgb", ...
00101 sensor_msgs/ChannelFloat32[] channels       
00102 
00103 
00104 
00105 ================================================================================
00106 MSG: geometry_msgs/Pose
00107 # A representation of pose in free space, composed of postion and orientation. 
00108 Point position
00109 Quaternion orientation
00110 
00111 ================================================================================
00112 MSG: geometry_msgs/Point
00113 # This contains the position of a point in free space
00114 float64 x
00115 float64 y
00116 float64 z
00117 
00118 ================================================================================
00119 MSG: geometry_msgs/Quaternion
00120 # This represents an orientation in free space in quaternion form.
00121 
00122 float64 x
00123 float64 y
00124 float64 z
00125 float64 w
00126 
00127 ================================================================================
00128 MSG: sensor_msgs/ChannelFloat32
00129 # This message is used by the PointCloud message to hold optional data
00130 # associated with each point in the cloud. The length of the values
00131 # array should be the same as the length of the points array in the
00132 # PointCloud, and each value should be associated with the corresponding
00133 # point.
00134 
00135 # Channel names in existing practice include:
00136 #   "u", "v" - row and column (respectively) in the left stereo image.
00137 #              This is opposite to usual conventions but remains for
00138 #              historical reasons. The newer PointCloud2 message has no
00139 #              such problem.
00140 #   "rgb" - For point clouds produced by color stereo cameras. uint8
00141 #           (R,G,B) values packed into the least significant 24 bits,
00142 #           in order.
00143 #   "intensity" - laser or pixel intensity.
00144 #   "distance"
00145 
00146 # The channel name should give semantics of the channel (e.g.
00147 # "intensity" instead of "value").
00148 string name
00149 
00150 # The values array should be 1-1 with the elements of the associated
00151 # PointCloud.
00152 float32[] values
00153 
00154 ================================================================================
00155 MSG: articulation_msgs/ParamMsg
00156 # Single parameter passed to or from model fitting
00157 #
00158 # This mechanism allows to flexibly pass parameters to 
00159 # model fitting (and vice versa). Note that these parameters 
00160 # are model-specific: A client may supply additional
00161 # parameters to the model estimator, and, similarly, a estimator
00162 # may add the estimated model parameters to the model message.
00163 # When the model is then evaluated, for example to make predictions
00164 # or to compute the likelihood, the model class can then use
00165 # these parameters.
00166 #
00167 # A parameter has a name, a value, and a type. The type globally
00168 # indicates whether it is a prior parameter (prior to model fitting),
00169 # or a model parameter (found during model fitting, using a maximum-
00170 # likelihood estimator), or a cached evaluation (e.g., the likelihood
00171 # or the BIC are a typical "side"-product of model estimation, and
00172 # can therefore already be cached).
00173 #
00174 # For a list of currently used parameters, see the documentation at
00175 # http://www.ros.org/wiki/articulation_models
00176 #
00177 
00178 uint8 PRIOR=0   # indicates a prior model parameter 
00179                 # (e.g., "sigma_position")
00180 uint8 PARAM=1   # indicates a estimated model parameter 
00181                 # (e.g., "rot_radius", the estimated radius)
00182 uint8 EVAL=2    # indicates a cached evaluation of the model, given 
00183                 # the current trajectory
00184                 # (e.g., "loglikelihood", the log likelihood of the
00185                 # data, given the model and its parameters)
00186 
00187 string name     # name of the parameter
00188 float64 value   # value of the parameter
00189 uint8 type      # type of the parameter (PRIOR, PARAM, EVAL)
00190 
00191 
00192 ================================================================================
00193 MSG: articulation_msgs/ModelMsg
00194 # Single kinematic model
00195 #
00196 # A kinematic model is defined by its model class name, and a set of parameters. 
00197 # The client may additionally specify a model id, that can be used to colorize the
00198 # model when visualized using the RVIZ model display.
00199 # 
00200 # For a list of currently implemented models, see the documetation at
00201 # http://www.ros.org/wiki/articulation_models
00202 #
00203 #
00204 
00205 std_msgs/Header header                        # frame and timestamp
00206 
00207 int32 id                             # user specified model id
00208 string name                          # name of the model family (e.g. "rotational",
00209                                      # "prismatic", "pca-gp", "rigid")
00210 articulation_msgs/ParamMsg[] params  # model parameters
00211 articulation_msgs/TrackMsg track     # trajectory from which the model is estimated, or
00212                                      # that is evaluated using the model
00213 
00214 ================================================================================
00215 MSG: visualization_msgs/MarkerArray
00216 Marker[] markers
00217 
00218 ================================================================================
00219 MSG: visualization_msgs/Marker
00220 # See http://www.ros.org/wiki/rviz/DisplayTypes/Marker and http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes for more information on using this message with rviz
00221 
00222 uint8 ARROW=0
00223 uint8 CUBE=1
00224 uint8 SPHERE=2
00225 uint8 CYLINDER=3
00226 uint8 LINE_STRIP=4
00227 uint8 LINE_LIST=5
00228 uint8 CUBE_LIST=6
00229 uint8 SPHERE_LIST=7
00230 uint8 POINTS=8
00231 uint8 TEXT_VIEW_FACING=9
00232 uint8 MESH_RESOURCE=10
00233 uint8 TRIANGLE_LIST=11
00234 
00235 uint8 ADD=0
00236 uint8 MODIFY=0
00237 uint8 DELETE=2
00238 
00239 Header header                        # header for time/frame information
00240 string ns                            # Namespace to place this object in... used in conjunction with id to create a unique name for the object
00241 int32 id                                         # object ID useful in conjunction with the namespace for manipulating and deleting the object later
00242 int32 type                                     # Type of object
00243 int32 action                           # 0 add/modify an object, 1 (deprecated), 2 deletes an object
00244 geometry_msgs/Pose pose                 # Pose of the object
00245 geometry_msgs/Vector3 scale             # Scale of the object 1,1,1 means default (usually 1 meter square)
00246 std_msgs/ColorRGBA color             # Color [0.0-1.0]
00247 duration lifetime                    # How long the object should last before being automatically deleted.  0 means forever
00248 bool frame_locked                    # If this marker should be frame-locked, i.e. retransformed into its frame every timestep
00249 
00250 #Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)
00251 geometry_msgs/Point[] points
00252 #Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)
00253 #number of colors must either be 0 or equal to the number of points
00254 #NOTE: alpha is not yet used
00255 std_msgs/ColorRGBA[] colors
00256 
00257 # NOTE: only used for text markers
00258 string text
00259 
00260 # NOTE: only used for MESH_RESOURCE markers
00261 string mesh_resource
00262 bool mesh_use_embedded_materials
00263 
00264 ================================================================================
00265 MSG: geometry_msgs/Vector3
00266 # This represents a vector in free space. 
00267 
00268 float64 x
00269 float64 y
00270 float64 z
00271 ================================================================================
00272 MSG: std_msgs/ColorRGBA
00273 float32 r
00274 float32 g
00275 float32 b
00276 float32 a
00277 
00278 """
00279   __slots__ = ['object']
00280   _slot_types = ['articulation_msgs/ArticulatedObjectMsg']
00281 
00282   def __init__(self, *args, **kwds):
00283     """
00284     Constructor. Any message fields that are implicitly/explicitly
00285     set to None will be assigned a default value. The recommend
00286     use is keyword arguments as this is more robust to future message
00287     changes.  You cannot mix in-order arguments and keyword arguments.
00288 
00289     The available fields are:
00290        object
00291 
00292     :param args: complete set of field values, in .msg order
00293     :param kwds: use keyword arguments corresponding to message field names
00294     to set specific fields.
00295     """
00296     if args or kwds:
00297       super(ArticulatedObjectSrvRequest, self).__init__(*args, **kwds)
00298       #message fields cannot be None, assign default values for those that are
00299       if self.object is None:
00300         self.object = articulation_msgs.msg.ArticulatedObjectMsg()
00301     else:
00302       self.object = articulation_msgs.msg.ArticulatedObjectMsg()
00303 
00304   def _get_types(self):
00305     """
00306     internal API method
00307     """
00308     return self._slot_types
00309 
00310   def serialize(self, buff):
00311     """
00312     serialize message into buffer
00313     :param buff: buffer, ``StringIO``
00314     """
00315     try:
00316       _x = self
00317       buff.write(_struct_3I.pack(_x.object.header.seq, _x.object.header.stamp.secs, _x.object.header.stamp.nsecs))
00318       _x = self.object.header.frame_id
00319       length = len(_x)
00320       if python3 or type(_x) == unicode:
00321         _x = _x.encode('utf-8')
00322         length = len(_x)
00323       buff.write(struct.pack('<I%ss'%length, length, _x))
00324       length = len(self.object.parts)
00325       buff.write(_struct_I.pack(length))
00326       for val1 in self.object.parts:
00327         _v1 = val1.header
00328         buff.write(_struct_I.pack(_v1.seq))
00329         _v2 = _v1.stamp
00330         _x = _v2
00331         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00332         _x = _v1.frame_id
00333         length = len(_x)
00334         if python3 or type(_x) == unicode:
00335           _x = _x.encode('utf-8')
00336           length = len(_x)
00337         buff.write(struct.pack('<I%ss'%length, length, _x))
00338         buff.write(_struct_i.pack(val1.id))
00339         length = len(val1.pose)
00340         buff.write(_struct_I.pack(length))
00341         for val2 in val1.pose:
00342           _v3 = val2.position
00343           _x = _v3
00344           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00345           _v4 = val2.orientation
00346           _x = _v4
00347           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00348         length = len(val1.pose_headers)
00349         buff.write(_struct_I.pack(length))
00350         for val2 in val1.pose_headers:
00351           buff.write(_struct_I.pack(val2.seq))
00352           _v5 = val2.stamp
00353           _x = _v5
00354           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00355           _x = val2.frame_id
00356           length = len(_x)
00357           if python3 or type(_x) == unicode:
00358             _x = _x.encode('utf-8')
00359             length = len(_x)
00360           buff.write(struct.pack('<I%ss'%length, length, _x))
00361         length = len(val1.pose_projected)
00362         buff.write(_struct_I.pack(length))
00363         for val2 in val1.pose_projected:
00364           _v6 = val2.position
00365           _x = _v6
00366           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00367           _v7 = val2.orientation
00368           _x = _v7
00369           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00370         length = len(val1.pose_resampled)
00371         buff.write(_struct_I.pack(length))
00372         for val2 in val1.pose_resampled:
00373           _v8 = val2.position
00374           _x = _v8
00375           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00376           _v9 = val2.orientation
00377           _x = _v9
00378           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00379         length = len(val1.pose_flags)
00380         buff.write(_struct_I.pack(length))
00381         pattern = '<%sI'%length
00382         buff.write(struct.pack(pattern, *val1.pose_flags))
00383         length = len(val1.channels)
00384         buff.write(_struct_I.pack(length))
00385         for val2 in val1.channels:
00386           _x = val2.name
00387           length = len(_x)
00388           if python3 or type(_x) == unicode:
00389             _x = _x.encode('utf-8')
00390             length = len(_x)
00391           buff.write(struct.pack('<I%ss'%length, length, _x))
00392           length = len(val2.values)
00393           buff.write(_struct_I.pack(length))
00394           pattern = '<%sf'%length
00395           buff.write(struct.pack(pattern, *val2.values))
00396       length = len(self.object.params)
00397       buff.write(_struct_I.pack(length))
00398       for val1 in self.object.params:
00399         _x = val1.name
00400         length = len(_x)
00401         if python3 or type(_x) == unicode:
00402           _x = _x.encode('utf-8')
00403           length = len(_x)
00404         buff.write(struct.pack('<I%ss'%length, length, _x))
00405         _x = val1
00406         buff.write(_struct_dB.pack(_x.value, _x.type))
00407       length = len(self.object.models)
00408       buff.write(_struct_I.pack(length))
00409       for val1 in self.object.models:
00410         _v10 = val1.header
00411         buff.write(_struct_I.pack(_v10.seq))
00412         _v11 = _v10.stamp
00413         _x = _v11
00414         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00415         _x = _v10.frame_id
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         buff.write(_struct_i.pack(val1.id))
00422         _x = val1.name
00423         length = len(_x)
00424         if python3 or type(_x) == unicode:
00425           _x = _x.encode('utf-8')
00426           length = len(_x)
00427         buff.write(struct.pack('<I%ss'%length, length, _x))
00428         length = len(val1.params)
00429         buff.write(_struct_I.pack(length))
00430         for val2 in val1.params:
00431           _x = val2.name
00432           length = len(_x)
00433           if python3 or type(_x) == unicode:
00434             _x = _x.encode('utf-8')
00435             length = len(_x)
00436           buff.write(struct.pack('<I%ss'%length, length, _x))
00437           _x = val2
00438           buff.write(_struct_dB.pack(_x.value, _x.type))
00439         _v12 = val1.track
00440         _v13 = _v12.header
00441         buff.write(_struct_I.pack(_v13.seq))
00442         _v14 = _v13.stamp
00443         _x = _v14
00444         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00445         _x = _v13.frame_id
00446         length = len(_x)
00447         if python3 or type(_x) == unicode:
00448           _x = _x.encode('utf-8')
00449           length = len(_x)
00450         buff.write(struct.pack('<I%ss'%length, length, _x))
00451         buff.write(_struct_i.pack(_v12.id))
00452         length = len(_v12.pose)
00453         buff.write(_struct_I.pack(length))
00454         for val3 in _v12.pose:
00455           _v15 = val3.position
00456           _x = _v15
00457           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00458           _v16 = val3.orientation
00459           _x = _v16
00460           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00461         length = len(_v12.pose_headers)
00462         buff.write(_struct_I.pack(length))
00463         for val3 in _v12.pose_headers:
00464           buff.write(_struct_I.pack(val3.seq))
00465           _v17 = val3.stamp
00466           _x = _v17
00467           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00468           _x = val3.frame_id
00469           length = len(_x)
00470           if python3 or type(_x) == unicode:
00471             _x = _x.encode('utf-8')
00472             length = len(_x)
00473           buff.write(struct.pack('<I%ss'%length, length, _x))
00474         length = len(_v12.pose_projected)
00475         buff.write(_struct_I.pack(length))
00476         for val3 in _v12.pose_projected:
00477           _v18 = val3.position
00478           _x = _v18
00479           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00480           _v19 = val3.orientation
00481           _x = _v19
00482           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00483         length = len(_v12.pose_resampled)
00484         buff.write(_struct_I.pack(length))
00485         for val3 in _v12.pose_resampled:
00486           _v20 = val3.position
00487           _x = _v20
00488           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00489           _v21 = val3.orientation
00490           _x = _v21
00491           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00492         length = len(_v12.pose_flags)
00493         buff.write(_struct_I.pack(length))
00494         pattern = '<%sI'%length
00495         buff.write(struct.pack(pattern, *_v12.pose_flags))
00496         length = len(_v12.channels)
00497         buff.write(_struct_I.pack(length))
00498         for val3 in _v12.channels:
00499           _x = val3.name
00500           length = len(_x)
00501           if python3 or type(_x) == unicode:
00502             _x = _x.encode('utf-8')
00503             length = len(_x)
00504           buff.write(struct.pack('<I%ss'%length, length, _x))
00505           length = len(val3.values)
00506           buff.write(_struct_I.pack(length))
00507           pattern = '<%sf'%length
00508           buff.write(struct.pack(pattern, *val3.values))
00509       length = len(self.object.markers.markers)
00510       buff.write(_struct_I.pack(length))
00511       for val1 in self.object.markers.markers:
00512         _v22 = val1.header
00513         buff.write(_struct_I.pack(_v22.seq))
00514         _v23 = _v22.stamp
00515         _x = _v23
00516         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00517         _x = _v22.frame_id
00518         length = len(_x)
00519         if python3 or type(_x) == unicode:
00520           _x = _x.encode('utf-8')
00521           length = len(_x)
00522         buff.write(struct.pack('<I%ss'%length, length, _x))
00523         _x = val1.ns
00524         length = len(_x)
00525         if python3 or type(_x) == unicode:
00526           _x = _x.encode('utf-8')
00527           length = len(_x)
00528         buff.write(struct.pack('<I%ss'%length, length, _x))
00529         _x = val1
00530         buff.write(_struct_3i.pack(_x.id, _x.type, _x.action))
00531         _v24 = val1.pose
00532         _v25 = _v24.position
00533         _x = _v25
00534         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00535         _v26 = _v24.orientation
00536         _x = _v26
00537         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00538         _v27 = val1.scale
00539         _x = _v27
00540         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00541         _v28 = val1.color
00542         _x = _v28
00543         buff.write(_struct_4f.pack(_x.r, _x.g, _x.b, _x.a))
00544         _v29 = val1.lifetime
00545         _x = _v29
00546         buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00547         buff.write(_struct_B.pack(val1.frame_locked))
00548         length = len(val1.points)
00549         buff.write(_struct_I.pack(length))
00550         for val2 in val1.points:
00551           _x = val2
00552           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00553         length = len(val1.colors)
00554         buff.write(_struct_I.pack(length))
00555         for val2 in val1.colors:
00556           _x = val2
00557           buff.write(_struct_4f.pack(_x.r, _x.g, _x.b, _x.a))
00558         _x = val1.text
00559         length = len(_x)
00560         if python3 or type(_x) == unicode:
00561           _x = _x.encode('utf-8')
00562           length = len(_x)
00563         buff.write(struct.pack('<I%ss'%length, length, _x))
00564         _x = val1.mesh_resource
00565         length = len(_x)
00566         if python3 or type(_x) == unicode:
00567           _x = _x.encode('utf-8')
00568           length = len(_x)
00569         buff.write(struct.pack('<I%ss'%length, length, _x))
00570         buff.write(_struct_B.pack(val1.mesh_use_embedded_materials))
00571     except struct.error as se: self._check_types(se)
00572     except TypeError as te: self._check_types(te)
00573 
00574   def deserialize(self, str):
00575     """
00576     unpack serialized message in str into this message instance
00577     :param str: byte array of serialized message, ``str``
00578     """
00579     try:
00580       if self.object is None:
00581         self.object = articulation_msgs.msg.ArticulatedObjectMsg()
00582       end = 0
00583       _x = self
00584       start = end
00585       end += 12
00586       (_x.object.header.seq, _x.object.header.stamp.secs, _x.object.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00587       start = end
00588       end += 4
00589       (length,) = _struct_I.unpack(str[start:end])
00590       start = end
00591       end += length
00592       if python3:
00593         self.object.header.frame_id = str[start:end].decode('utf-8')
00594       else:
00595         self.object.header.frame_id = str[start:end]
00596       start = end
00597       end += 4
00598       (length,) = _struct_I.unpack(str[start:end])
00599       self.object.parts = []
00600       for i in range(0, length):
00601         val1 = articulation_msgs.msg.TrackMsg()
00602         _v30 = val1.header
00603         start = end
00604         end += 4
00605         (_v30.seq,) = _struct_I.unpack(str[start:end])
00606         _v31 = _v30.stamp
00607         _x = _v31
00608         start = end
00609         end += 8
00610         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00611         start = end
00612         end += 4
00613         (length,) = _struct_I.unpack(str[start:end])
00614         start = end
00615         end += length
00616         if python3:
00617           _v30.frame_id = str[start:end].decode('utf-8')
00618         else:
00619           _v30.frame_id = str[start:end]
00620         start = end
00621         end += 4
00622         (val1.id,) = _struct_i.unpack(str[start:end])
00623         start = end
00624         end += 4
00625         (length,) = _struct_I.unpack(str[start:end])
00626         val1.pose = []
00627         for i in range(0, length):
00628           val2 = geometry_msgs.msg.Pose()
00629           _v32 = val2.position
00630           _x = _v32
00631           start = end
00632           end += 24
00633           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00634           _v33 = val2.orientation
00635           _x = _v33
00636           start = end
00637           end += 32
00638           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00639           val1.pose.append(val2)
00640         start = end
00641         end += 4
00642         (length,) = _struct_I.unpack(str[start:end])
00643         val1.pose_headers = []
00644         for i in range(0, length):
00645           val2 = std_msgs.msg.Header()
00646           start = end
00647           end += 4
00648           (val2.seq,) = _struct_I.unpack(str[start:end])
00649           _v34 = val2.stamp
00650           _x = _v34
00651           start = end
00652           end += 8
00653           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00654           start = end
00655           end += 4
00656           (length,) = _struct_I.unpack(str[start:end])
00657           start = end
00658           end += length
00659           if python3:
00660             val2.frame_id = str[start:end].decode('utf-8')
00661           else:
00662             val2.frame_id = str[start:end]
00663           val1.pose_headers.append(val2)
00664         start = end
00665         end += 4
00666         (length,) = _struct_I.unpack(str[start:end])
00667         val1.pose_projected = []
00668         for i in range(0, length):
00669           val2 = geometry_msgs.msg.Pose()
00670           _v35 = val2.position
00671           _x = _v35
00672           start = end
00673           end += 24
00674           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00675           _v36 = val2.orientation
00676           _x = _v36
00677           start = end
00678           end += 32
00679           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00680           val1.pose_projected.append(val2)
00681         start = end
00682         end += 4
00683         (length,) = _struct_I.unpack(str[start:end])
00684         val1.pose_resampled = []
00685         for i in range(0, length):
00686           val2 = geometry_msgs.msg.Pose()
00687           _v37 = val2.position
00688           _x = _v37
00689           start = end
00690           end += 24
00691           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00692           _v38 = val2.orientation
00693           _x = _v38
00694           start = end
00695           end += 32
00696           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00697           val1.pose_resampled.append(val2)
00698         start = end
00699         end += 4
00700         (length,) = _struct_I.unpack(str[start:end])
00701         pattern = '<%sI'%length
00702         start = end
00703         end += struct.calcsize(pattern)
00704         val1.pose_flags = struct.unpack(pattern, str[start:end])
00705         start = end
00706         end += 4
00707         (length,) = _struct_I.unpack(str[start:end])
00708         val1.channels = []
00709         for i in range(0, length):
00710           val2 = sensor_msgs.msg.ChannelFloat32()
00711           start = end
00712           end += 4
00713           (length,) = _struct_I.unpack(str[start:end])
00714           start = end
00715           end += length
00716           if python3:
00717             val2.name = str[start:end].decode('utf-8')
00718           else:
00719             val2.name = str[start:end]
00720           start = end
00721           end += 4
00722           (length,) = _struct_I.unpack(str[start:end])
00723           pattern = '<%sf'%length
00724           start = end
00725           end += struct.calcsize(pattern)
00726           val2.values = struct.unpack(pattern, str[start:end])
00727           val1.channels.append(val2)
00728         self.object.parts.append(val1)
00729       start = end
00730       end += 4
00731       (length,) = _struct_I.unpack(str[start:end])
00732       self.object.params = []
00733       for i in range(0, length):
00734         val1 = articulation_msgs.msg.ParamMsg()
00735         start = end
00736         end += 4
00737         (length,) = _struct_I.unpack(str[start:end])
00738         start = end
00739         end += length
00740         if python3:
00741           val1.name = str[start:end].decode('utf-8')
00742         else:
00743           val1.name = str[start:end]
00744         _x = val1
00745         start = end
00746         end += 9
00747         (_x.value, _x.type,) = _struct_dB.unpack(str[start:end])
00748         self.object.params.append(val1)
00749       start = end
00750       end += 4
00751       (length,) = _struct_I.unpack(str[start:end])
00752       self.object.models = []
00753       for i in range(0, length):
00754         val1 = articulation_msgs.msg.ModelMsg()
00755         _v39 = val1.header
00756         start = end
00757         end += 4
00758         (_v39.seq,) = _struct_I.unpack(str[start:end])
00759         _v40 = _v39.stamp
00760         _x = _v40
00761         start = end
00762         end += 8
00763         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00764         start = end
00765         end += 4
00766         (length,) = _struct_I.unpack(str[start:end])
00767         start = end
00768         end += length
00769         if python3:
00770           _v39.frame_id = str[start:end].decode('utf-8')
00771         else:
00772           _v39.frame_id = str[start:end]
00773         start = end
00774         end += 4
00775         (val1.id,) = _struct_i.unpack(str[start:end])
00776         start = end
00777         end += 4
00778         (length,) = _struct_I.unpack(str[start:end])
00779         start = end
00780         end += length
00781         if python3:
00782           val1.name = str[start:end].decode('utf-8')
00783         else:
00784           val1.name = str[start:end]
00785         start = end
00786         end += 4
00787         (length,) = _struct_I.unpack(str[start:end])
00788         val1.params = []
00789         for i in range(0, length):
00790           val2 = articulation_msgs.msg.ParamMsg()
00791           start = end
00792           end += 4
00793           (length,) = _struct_I.unpack(str[start:end])
00794           start = end
00795           end += length
00796           if python3:
00797             val2.name = str[start:end].decode('utf-8')
00798           else:
00799             val2.name = str[start:end]
00800           _x = val2
00801           start = end
00802           end += 9
00803           (_x.value, _x.type,) = _struct_dB.unpack(str[start:end])
00804           val1.params.append(val2)
00805         _v41 = val1.track
00806         _v42 = _v41.header
00807         start = end
00808         end += 4
00809         (_v42.seq,) = _struct_I.unpack(str[start:end])
00810         _v43 = _v42.stamp
00811         _x = _v43
00812         start = end
00813         end += 8
00814         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00815         start = end
00816         end += 4
00817         (length,) = _struct_I.unpack(str[start:end])
00818         start = end
00819         end += length
00820         if python3:
00821           _v42.frame_id = str[start:end].decode('utf-8')
00822         else:
00823           _v42.frame_id = str[start:end]
00824         start = end
00825         end += 4
00826         (_v41.id,) = _struct_i.unpack(str[start:end])
00827         start = end
00828         end += 4
00829         (length,) = _struct_I.unpack(str[start:end])
00830         _v41.pose = []
00831         for i in range(0, length):
00832           val3 = geometry_msgs.msg.Pose()
00833           _v44 = val3.position
00834           _x = _v44
00835           start = end
00836           end += 24
00837           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00838           _v45 = val3.orientation
00839           _x = _v45
00840           start = end
00841           end += 32
00842           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00843           _v41.pose.append(val3)
00844         start = end
00845         end += 4
00846         (length,) = _struct_I.unpack(str[start:end])
00847         _v41.pose_headers = []
00848         for i in range(0, length):
00849           val3 = std_msgs.msg.Header()
00850           start = end
00851           end += 4
00852           (val3.seq,) = _struct_I.unpack(str[start:end])
00853           _v46 = val3.stamp
00854           _x = _v46
00855           start = end
00856           end += 8
00857           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00858           start = end
00859           end += 4
00860           (length,) = _struct_I.unpack(str[start:end])
00861           start = end
00862           end += length
00863           if python3:
00864             val3.frame_id = str[start:end].decode('utf-8')
00865           else:
00866             val3.frame_id = str[start:end]
00867           _v41.pose_headers.append(val3)
00868         start = end
00869         end += 4
00870         (length,) = _struct_I.unpack(str[start:end])
00871         _v41.pose_projected = []
00872         for i in range(0, length):
00873           val3 = geometry_msgs.msg.Pose()
00874           _v47 = val3.position
00875           _x = _v47
00876           start = end
00877           end += 24
00878           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00879           _v48 = val3.orientation
00880           _x = _v48
00881           start = end
00882           end += 32
00883           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00884           _v41.pose_projected.append(val3)
00885         start = end
00886         end += 4
00887         (length,) = _struct_I.unpack(str[start:end])
00888         _v41.pose_resampled = []
00889         for i in range(0, length):
00890           val3 = geometry_msgs.msg.Pose()
00891           _v49 = val3.position
00892           _x = _v49
00893           start = end
00894           end += 24
00895           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00896           _v50 = val3.orientation
00897           _x = _v50
00898           start = end
00899           end += 32
00900           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00901           _v41.pose_resampled.append(val3)
00902         start = end
00903         end += 4
00904         (length,) = _struct_I.unpack(str[start:end])
00905         pattern = '<%sI'%length
00906         start = end
00907         end += struct.calcsize(pattern)
00908         _v41.pose_flags = struct.unpack(pattern, str[start:end])
00909         start = end
00910         end += 4
00911         (length,) = _struct_I.unpack(str[start:end])
00912         _v41.channels = []
00913         for i in range(0, length):
00914           val3 = sensor_msgs.msg.ChannelFloat32()
00915           start = end
00916           end += 4
00917           (length,) = _struct_I.unpack(str[start:end])
00918           start = end
00919           end += length
00920           if python3:
00921             val3.name = str[start:end].decode('utf-8')
00922           else:
00923             val3.name = str[start:end]
00924           start = end
00925           end += 4
00926           (length,) = _struct_I.unpack(str[start:end])
00927           pattern = '<%sf'%length
00928           start = end
00929           end += struct.calcsize(pattern)
00930           val3.values = struct.unpack(pattern, str[start:end])
00931           _v41.channels.append(val3)
00932         self.object.models.append(val1)
00933       start = end
00934       end += 4
00935       (length,) = _struct_I.unpack(str[start:end])
00936       self.object.markers.markers = []
00937       for i in range(0, length):
00938         val1 = visualization_msgs.msg.Marker()
00939         _v51 = val1.header
00940         start = end
00941         end += 4
00942         (_v51.seq,) = _struct_I.unpack(str[start:end])
00943         _v52 = _v51.stamp
00944         _x = _v52
00945         start = end
00946         end += 8
00947         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00948         start = end
00949         end += 4
00950         (length,) = _struct_I.unpack(str[start:end])
00951         start = end
00952         end += length
00953         if python3:
00954           _v51.frame_id = str[start:end].decode('utf-8')
00955         else:
00956           _v51.frame_id = str[start:end]
00957         start = end
00958         end += 4
00959         (length,) = _struct_I.unpack(str[start:end])
00960         start = end
00961         end += length
00962         if python3:
00963           val1.ns = str[start:end].decode('utf-8')
00964         else:
00965           val1.ns = str[start:end]
00966         _x = val1
00967         start = end
00968         end += 12
00969         (_x.id, _x.type, _x.action,) = _struct_3i.unpack(str[start:end])
00970         _v53 = val1.pose
00971         _v54 = _v53.position
00972         _x = _v54
00973         start = end
00974         end += 24
00975         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00976         _v55 = _v53.orientation
00977         _x = _v55
00978         start = end
00979         end += 32
00980         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00981         _v56 = val1.scale
00982         _x = _v56
00983         start = end
00984         end += 24
00985         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00986         _v57 = val1.color
00987         _x = _v57
00988         start = end
00989         end += 16
00990         (_x.r, _x.g, _x.b, _x.a,) = _struct_4f.unpack(str[start:end])
00991         _v58 = val1.lifetime
00992         _x = _v58
00993         start = end
00994         end += 8
00995         (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00996         start = end
00997         end += 1
00998         (val1.frame_locked,) = _struct_B.unpack(str[start:end])
00999         val1.frame_locked = bool(val1.frame_locked)
01000         start = end
01001         end += 4
01002         (length,) = _struct_I.unpack(str[start:end])
01003         val1.points = []
01004         for i in range(0, length):
01005           val2 = geometry_msgs.msg.Point()
01006           _x = val2
01007           start = end
01008           end += 24
01009           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01010           val1.points.append(val2)
01011         start = end
01012         end += 4
01013         (length,) = _struct_I.unpack(str[start:end])
01014         val1.colors = []
01015         for i in range(0, length):
01016           val2 = std_msgs.msg.ColorRGBA()
01017           _x = val2
01018           start = end
01019           end += 16
01020           (_x.r, _x.g, _x.b, _x.a,) = _struct_4f.unpack(str[start:end])
01021           val1.colors.append(val2)
01022         start = end
01023         end += 4
01024         (length,) = _struct_I.unpack(str[start:end])
01025         start = end
01026         end += length
01027         if python3:
01028           val1.text = str[start:end].decode('utf-8')
01029         else:
01030           val1.text = str[start:end]
01031         start = end
01032         end += 4
01033         (length,) = _struct_I.unpack(str[start:end])
01034         start = end
01035         end += length
01036         if python3:
01037           val1.mesh_resource = str[start:end].decode('utf-8')
01038         else:
01039           val1.mesh_resource = str[start:end]
01040         start = end
01041         end += 1
01042         (val1.mesh_use_embedded_materials,) = _struct_B.unpack(str[start:end])
01043         val1.mesh_use_embedded_materials = bool(val1.mesh_use_embedded_materials)
01044         self.object.markers.markers.append(val1)
01045       return self
01046     except struct.error as e:
01047       raise genpy.DeserializationError(e) #most likely buffer underfill
01048 
01049 
01050   def serialize_numpy(self, buff, numpy):
01051     """
01052     serialize message with numpy array types into buffer
01053     :param buff: buffer, ``StringIO``
01054     :param numpy: numpy python module
01055     """
01056     try:
01057       _x = self
01058       buff.write(_struct_3I.pack(_x.object.header.seq, _x.object.header.stamp.secs, _x.object.header.stamp.nsecs))
01059       _x = self.object.header.frame_id
01060       length = len(_x)
01061       if python3 or type(_x) == unicode:
01062         _x = _x.encode('utf-8')
01063         length = len(_x)
01064       buff.write(struct.pack('<I%ss'%length, length, _x))
01065       length = len(self.object.parts)
01066       buff.write(_struct_I.pack(length))
01067       for val1 in self.object.parts:
01068         _v59 = val1.header
01069         buff.write(_struct_I.pack(_v59.seq))
01070         _v60 = _v59.stamp
01071         _x = _v60
01072         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01073         _x = _v59.frame_id
01074         length = len(_x)
01075         if python3 or type(_x) == unicode:
01076           _x = _x.encode('utf-8')
01077           length = len(_x)
01078         buff.write(struct.pack('<I%ss'%length, length, _x))
01079         buff.write(_struct_i.pack(val1.id))
01080         length = len(val1.pose)
01081         buff.write(_struct_I.pack(length))
01082         for val2 in val1.pose:
01083           _v61 = val2.position
01084           _x = _v61
01085           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01086           _v62 = val2.orientation
01087           _x = _v62
01088           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01089         length = len(val1.pose_headers)
01090         buff.write(_struct_I.pack(length))
01091         for val2 in val1.pose_headers:
01092           buff.write(_struct_I.pack(val2.seq))
01093           _v63 = val2.stamp
01094           _x = _v63
01095           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01096           _x = val2.frame_id
01097           length = len(_x)
01098           if python3 or type(_x) == unicode:
01099             _x = _x.encode('utf-8')
01100             length = len(_x)
01101           buff.write(struct.pack('<I%ss'%length, length, _x))
01102         length = len(val1.pose_projected)
01103         buff.write(_struct_I.pack(length))
01104         for val2 in val1.pose_projected:
01105           _v64 = val2.position
01106           _x = _v64
01107           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01108           _v65 = val2.orientation
01109           _x = _v65
01110           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01111         length = len(val1.pose_resampled)
01112         buff.write(_struct_I.pack(length))
01113         for val2 in val1.pose_resampled:
01114           _v66 = val2.position
01115           _x = _v66
01116           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01117           _v67 = val2.orientation
01118           _x = _v67
01119           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01120         length = len(val1.pose_flags)
01121         buff.write(_struct_I.pack(length))
01122         pattern = '<%sI'%length
01123         buff.write(val1.pose_flags.tostring())
01124         length = len(val1.channels)
01125         buff.write(_struct_I.pack(length))
01126         for val2 in val1.channels:
01127           _x = val2.name
01128           length = len(_x)
01129           if python3 or type(_x) == unicode:
01130             _x = _x.encode('utf-8')
01131             length = len(_x)
01132           buff.write(struct.pack('<I%ss'%length, length, _x))
01133           length = len(val2.values)
01134           buff.write(_struct_I.pack(length))
01135           pattern = '<%sf'%length
01136           buff.write(val2.values.tostring())
01137       length = len(self.object.params)
01138       buff.write(_struct_I.pack(length))
01139       for val1 in self.object.params:
01140         _x = val1.name
01141         length = len(_x)
01142         if python3 or type(_x) == unicode:
01143           _x = _x.encode('utf-8')
01144           length = len(_x)
01145         buff.write(struct.pack('<I%ss'%length, length, _x))
01146         _x = val1
01147         buff.write(_struct_dB.pack(_x.value, _x.type))
01148       length = len(self.object.models)
01149       buff.write(_struct_I.pack(length))
01150       for val1 in self.object.models:
01151         _v68 = val1.header
01152         buff.write(_struct_I.pack(_v68.seq))
01153         _v69 = _v68.stamp
01154         _x = _v69
01155         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01156         _x = _v68.frame_id
01157         length = len(_x)
01158         if python3 or type(_x) == unicode:
01159           _x = _x.encode('utf-8')
01160           length = len(_x)
01161         buff.write(struct.pack('<I%ss'%length, length, _x))
01162         buff.write(_struct_i.pack(val1.id))
01163         _x = val1.name
01164         length = len(_x)
01165         if python3 or type(_x) == unicode:
01166           _x = _x.encode('utf-8')
01167           length = len(_x)
01168         buff.write(struct.pack('<I%ss'%length, length, _x))
01169         length = len(val1.params)
01170         buff.write(_struct_I.pack(length))
01171         for val2 in val1.params:
01172           _x = val2.name
01173           length = len(_x)
01174           if python3 or type(_x) == unicode:
01175             _x = _x.encode('utf-8')
01176             length = len(_x)
01177           buff.write(struct.pack('<I%ss'%length, length, _x))
01178           _x = val2
01179           buff.write(_struct_dB.pack(_x.value, _x.type))
01180         _v70 = val1.track
01181         _v71 = _v70.header
01182         buff.write(_struct_I.pack(_v71.seq))
01183         _v72 = _v71.stamp
01184         _x = _v72
01185         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01186         _x = _v71.frame_id
01187         length = len(_x)
01188         if python3 or type(_x) == unicode:
01189           _x = _x.encode('utf-8')
01190           length = len(_x)
01191         buff.write(struct.pack('<I%ss'%length, length, _x))
01192         buff.write(_struct_i.pack(_v70.id))
01193         length = len(_v70.pose)
01194         buff.write(_struct_I.pack(length))
01195         for val3 in _v70.pose:
01196           _v73 = val3.position
01197           _x = _v73
01198           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01199           _v74 = val3.orientation
01200           _x = _v74
01201           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01202         length = len(_v70.pose_headers)
01203         buff.write(_struct_I.pack(length))
01204         for val3 in _v70.pose_headers:
01205           buff.write(_struct_I.pack(val3.seq))
01206           _v75 = val3.stamp
01207           _x = _v75
01208           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01209           _x = val3.frame_id
01210           length = len(_x)
01211           if python3 or type(_x) == unicode:
01212             _x = _x.encode('utf-8')
01213             length = len(_x)
01214           buff.write(struct.pack('<I%ss'%length, length, _x))
01215         length = len(_v70.pose_projected)
01216         buff.write(_struct_I.pack(length))
01217         for val3 in _v70.pose_projected:
01218           _v76 = val3.position
01219           _x = _v76
01220           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01221           _v77 = val3.orientation
01222           _x = _v77
01223           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01224         length = len(_v70.pose_resampled)
01225         buff.write(_struct_I.pack(length))
01226         for val3 in _v70.pose_resampled:
01227           _v78 = val3.position
01228           _x = _v78
01229           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01230           _v79 = val3.orientation
01231           _x = _v79
01232           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01233         length = len(_v70.pose_flags)
01234         buff.write(_struct_I.pack(length))
01235         pattern = '<%sI'%length
01236         buff.write(_v70.pose_flags.tostring())
01237         length = len(_v70.channels)
01238         buff.write(_struct_I.pack(length))
01239         for val3 in _v70.channels:
01240           _x = val3.name
01241           length = len(_x)
01242           if python3 or type(_x) == unicode:
01243             _x = _x.encode('utf-8')
01244             length = len(_x)
01245           buff.write(struct.pack('<I%ss'%length, length, _x))
01246           length = len(val3.values)
01247           buff.write(_struct_I.pack(length))
01248           pattern = '<%sf'%length
01249           buff.write(val3.values.tostring())
01250       length = len(self.object.markers.markers)
01251       buff.write(_struct_I.pack(length))
01252       for val1 in self.object.markers.markers:
01253         _v80 = val1.header
01254         buff.write(_struct_I.pack(_v80.seq))
01255         _v81 = _v80.stamp
01256         _x = _v81
01257         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
01258         _x = _v80.frame_id
01259         length = len(_x)
01260         if python3 or type(_x) == unicode:
01261           _x = _x.encode('utf-8')
01262           length = len(_x)
01263         buff.write(struct.pack('<I%ss'%length, length, _x))
01264         _x = val1.ns
01265         length = len(_x)
01266         if python3 or type(_x) == unicode:
01267           _x = _x.encode('utf-8')
01268           length = len(_x)
01269         buff.write(struct.pack('<I%ss'%length, length, _x))
01270         _x = val1
01271         buff.write(_struct_3i.pack(_x.id, _x.type, _x.action))
01272         _v82 = val1.pose
01273         _v83 = _v82.position
01274         _x = _v83
01275         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01276         _v84 = _v82.orientation
01277         _x = _v84
01278         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
01279         _v85 = val1.scale
01280         _x = _v85
01281         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01282         _v86 = val1.color
01283         _x = _v86
01284         buff.write(_struct_4f.pack(_x.r, _x.g, _x.b, _x.a))
01285         _v87 = val1.lifetime
01286         _x = _v87
01287         buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
01288         buff.write(_struct_B.pack(val1.frame_locked))
01289         length = len(val1.points)
01290         buff.write(_struct_I.pack(length))
01291         for val2 in val1.points:
01292           _x = val2
01293           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
01294         length = len(val1.colors)
01295         buff.write(_struct_I.pack(length))
01296         for val2 in val1.colors:
01297           _x = val2
01298           buff.write(_struct_4f.pack(_x.r, _x.g, _x.b, _x.a))
01299         _x = val1.text
01300         length = len(_x)
01301         if python3 or type(_x) == unicode:
01302           _x = _x.encode('utf-8')
01303           length = len(_x)
01304         buff.write(struct.pack('<I%ss'%length, length, _x))
01305         _x = val1.mesh_resource
01306         length = len(_x)
01307         if python3 or type(_x) == unicode:
01308           _x = _x.encode('utf-8')
01309           length = len(_x)
01310         buff.write(struct.pack('<I%ss'%length, length, _x))
01311         buff.write(_struct_B.pack(val1.mesh_use_embedded_materials))
01312     except struct.error as se: self._check_types(se)
01313     except TypeError as te: self._check_types(te)
01314 
01315   def deserialize_numpy(self, str, numpy):
01316     """
01317     unpack serialized message in str into this message instance using numpy for array types
01318     :param str: byte array of serialized message, ``str``
01319     :param numpy: numpy python module
01320     """
01321     try:
01322       if self.object is None:
01323         self.object = articulation_msgs.msg.ArticulatedObjectMsg()
01324       end = 0
01325       _x = self
01326       start = end
01327       end += 12
01328       (_x.object.header.seq, _x.object.header.stamp.secs, _x.object.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
01329       start = end
01330       end += 4
01331       (length,) = _struct_I.unpack(str[start:end])
01332       start = end
01333       end += length
01334       if python3:
01335         self.object.header.frame_id = str[start:end].decode('utf-8')
01336       else:
01337         self.object.header.frame_id = str[start:end]
01338       start = end
01339       end += 4
01340       (length,) = _struct_I.unpack(str[start:end])
01341       self.object.parts = []
01342       for i in range(0, length):
01343         val1 = articulation_msgs.msg.TrackMsg()
01344         _v88 = val1.header
01345         start = end
01346         end += 4
01347         (_v88.seq,) = _struct_I.unpack(str[start:end])
01348         _v89 = _v88.stamp
01349         _x = _v89
01350         start = end
01351         end += 8
01352         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01353         start = end
01354         end += 4
01355         (length,) = _struct_I.unpack(str[start:end])
01356         start = end
01357         end += length
01358         if python3:
01359           _v88.frame_id = str[start:end].decode('utf-8')
01360         else:
01361           _v88.frame_id = str[start:end]
01362         start = end
01363         end += 4
01364         (val1.id,) = _struct_i.unpack(str[start:end])
01365         start = end
01366         end += 4
01367         (length,) = _struct_I.unpack(str[start:end])
01368         val1.pose = []
01369         for i in range(0, length):
01370           val2 = geometry_msgs.msg.Pose()
01371           _v90 = val2.position
01372           _x = _v90
01373           start = end
01374           end += 24
01375           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01376           _v91 = val2.orientation
01377           _x = _v91
01378           start = end
01379           end += 32
01380           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01381           val1.pose.append(val2)
01382         start = end
01383         end += 4
01384         (length,) = _struct_I.unpack(str[start:end])
01385         val1.pose_headers = []
01386         for i in range(0, length):
01387           val2 = std_msgs.msg.Header()
01388           start = end
01389           end += 4
01390           (val2.seq,) = _struct_I.unpack(str[start:end])
01391           _v92 = val2.stamp
01392           _x = _v92
01393           start = end
01394           end += 8
01395           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01396           start = end
01397           end += 4
01398           (length,) = _struct_I.unpack(str[start:end])
01399           start = end
01400           end += length
01401           if python3:
01402             val2.frame_id = str[start:end].decode('utf-8')
01403           else:
01404             val2.frame_id = str[start:end]
01405           val1.pose_headers.append(val2)
01406         start = end
01407         end += 4
01408         (length,) = _struct_I.unpack(str[start:end])
01409         val1.pose_projected = []
01410         for i in range(0, length):
01411           val2 = geometry_msgs.msg.Pose()
01412           _v93 = val2.position
01413           _x = _v93
01414           start = end
01415           end += 24
01416           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01417           _v94 = val2.orientation
01418           _x = _v94
01419           start = end
01420           end += 32
01421           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01422           val1.pose_projected.append(val2)
01423         start = end
01424         end += 4
01425         (length,) = _struct_I.unpack(str[start:end])
01426         val1.pose_resampled = []
01427         for i in range(0, length):
01428           val2 = geometry_msgs.msg.Pose()
01429           _v95 = val2.position
01430           _x = _v95
01431           start = end
01432           end += 24
01433           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01434           _v96 = val2.orientation
01435           _x = _v96
01436           start = end
01437           end += 32
01438           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01439           val1.pose_resampled.append(val2)
01440         start = end
01441         end += 4
01442         (length,) = _struct_I.unpack(str[start:end])
01443         pattern = '<%sI'%length
01444         start = end
01445         end += struct.calcsize(pattern)
01446         val1.pose_flags = numpy.frombuffer(str[start:end], dtype=numpy.uint32, count=length)
01447         start = end
01448         end += 4
01449         (length,) = _struct_I.unpack(str[start:end])
01450         val1.channels = []
01451         for i in range(0, length):
01452           val2 = sensor_msgs.msg.ChannelFloat32()
01453           start = end
01454           end += 4
01455           (length,) = _struct_I.unpack(str[start:end])
01456           start = end
01457           end += length
01458           if python3:
01459             val2.name = str[start:end].decode('utf-8')
01460           else:
01461             val2.name = str[start:end]
01462           start = end
01463           end += 4
01464           (length,) = _struct_I.unpack(str[start:end])
01465           pattern = '<%sf'%length
01466           start = end
01467           end += struct.calcsize(pattern)
01468           val2.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
01469           val1.channels.append(val2)
01470         self.object.parts.append(val1)
01471       start = end
01472       end += 4
01473       (length,) = _struct_I.unpack(str[start:end])
01474       self.object.params = []
01475       for i in range(0, length):
01476         val1 = articulation_msgs.msg.ParamMsg()
01477         start = end
01478         end += 4
01479         (length,) = _struct_I.unpack(str[start:end])
01480         start = end
01481         end += length
01482         if python3:
01483           val1.name = str[start:end].decode('utf-8')
01484         else:
01485           val1.name = str[start:end]
01486         _x = val1
01487         start = end
01488         end += 9
01489         (_x.value, _x.type,) = _struct_dB.unpack(str[start:end])
01490         self.object.params.append(val1)
01491       start = end
01492       end += 4
01493       (length,) = _struct_I.unpack(str[start:end])
01494       self.object.models = []
01495       for i in range(0, length):
01496         val1 = articulation_msgs.msg.ModelMsg()
01497         _v97 = val1.header
01498         start = end
01499         end += 4
01500         (_v97.seq,) = _struct_I.unpack(str[start:end])
01501         _v98 = _v97.stamp
01502         _x = _v98
01503         start = end
01504         end += 8
01505         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01506         start = end
01507         end += 4
01508         (length,) = _struct_I.unpack(str[start:end])
01509         start = end
01510         end += length
01511         if python3:
01512           _v97.frame_id = str[start:end].decode('utf-8')
01513         else:
01514           _v97.frame_id = str[start:end]
01515         start = end
01516         end += 4
01517         (val1.id,) = _struct_i.unpack(str[start:end])
01518         start = end
01519         end += 4
01520         (length,) = _struct_I.unpack(str[start:end])
01521         start = end
01522         end += length
01523         if python3:
01524           val1.name = str[start:end].decode('utf-8')
01525         else:
01526           val1.name = str[start:end]
01527         start = end
01528         end += 4
01529         (length,) = _struct_I.unpack(str[start:end])
01530         val1.params = []
01531         for i in range(0, length):
01532           val2 = articulation_msgs.msg.ParamMsg()
01533           start = end
01534           end += 4
01535           (length,) = _struct_I.unpack(str[start:end])
01536           start = end
01537           end += length
01538           if python3:
01539             val2.name = str[start:end].decode('utf-8')
01540           else:
01541             val2.name = str[start:end]
01542           _x = val2
01543           start = end
01544           end += 9
01545           (_x.value, _x.type,) = _struct_dB.unpack(str[start:end])
01546           val1.params.append(val2)
01547         _v99 = val1.track
01548         _v100 = _v99.header
01549         start = end
01550         end += 4
01551         (_v100.seq,) = _struct_I.unpack(str[start:end])
01552         _v101 = _v100.stamp
01553         _x = _v101
01554         start = end
01555         end += 8
01556         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01557         start = end
01558         end += 4
01559         (length,) = _struct_I.unpack(str[start:end])
01560         start = end
01561         end += length
01562         if python3:
01563           _v100.frame_id = str[start:end].decode('utf-8')
01564         else:
01565           _v100.frame_id = str[start:end]
01566         start = end
01567         end += 4
01568         (_v99.id,) = _struct_i.unpack(str[start:end])
01569         start = end
01570         end += 4
01571         (length,) = _struct_I.unpack(str[start:end])
01572         _v99.pose = []
01573         for i in range(0, length):
01574           val3 = geometry_msgs.msg.Pose()
01575           _v102 = val3.position
01576           _x = _v102
01577           start = end
01578           end += 24
01579           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01580           _v103 = val3.orientation
01581           _x = _v103
01582           start = end
01583           end += 32
01584           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01585           _v99.pose.append(val3)
01586         start = end
01587         end += 4
01588         (length,) = _struct_I.unpack(str[start:end])
01589         _v99.pose_headers = []
01590         for i in range(0, length):
01591           val3 = std_msgs.msg.Header()
01592           start = end
01593           end += 4
01594           (val3.seq,) = _struct_I.unpack(str[start:end])
01595           _v104 = val3.stamp
01596           _x = _v104
01597           start = end
01598           end += 8
01599           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01600           start = end
01601           end += 4
01602           (length,) = _struct_I.unpack(str[start:end])
01603           start = end
01604           end += length
01605           if python3:
01606             val3.frame_id = str[start:end].decode('utf-8')
01607           else:
01608             val3.frame_id = str[start:end]
01609           _v99.pose_headers.append(val3)
01610         start = end
01611         end += 4
01612         (length,) = _struct_I.unpack(str[start:end])
01613         _v99.pose_projected = []
01614         for i in range(0, length):
01615           val3 = geometry_msgs.msg.Pose()
01616           _v105 = val3.position
01617           _x = _v105
01618           start = end
01619           end += 24
01620           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01621           _v106 = val3.orientation
01622           _x = _v106
01623           start = end
01624           end += 32
01625           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01626           _v99.pose_projected.append(val3)
01627         start = end
01628         end += 4
01629         (length,) = _struct_I.unpack(str[start:end])
01630         _v99.pose_resampled = []
01631         for i in range(0, length):
01632           val3 = geometry_msgs.msg.Pose()
01633           _v107 = val3.position
01634           _x = _v107
01635           start = end
01636           end += 24
01637           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01638           _v108 = val3.orientation
01639           _x = _v108
01640           start = end
01641           end += 32
01642           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01643           _v99.pose_resampled.append(val3)
01644         start = end
01645         end += 4
01646         (length,) = _struct_I.unpack(str[start:end])
01647         pattern = '<%sI'%length
01648         start = end
01649         end += struct.calcsize(pattern)
01650         _v99.pose_flags = numpy.frombuffer(str[start:end], dtype=numpy.uint32, count=length)
01651         start = end
01652         end += 4
01653         (length,) = _struct_I.unpack(str[start:end])
01654         _v99.channels = []
01655         for i in range(0, length):
01656           val3 = sensor_msgs.msg.ChannelFloat32()
01657           start = end
01658           end += 4
01659           (length,) = _struct_I.unpack(str[start:end])
01660           start = end
01661           end += length
01662           if python3:
01663             val3.name = str[start:end].decode('utf-8')
01664           else:
01665             val3.name = str[start:end]
01666           start = end
01667           end += 4
01668           (length,) = _struct_I.unpack(str[start:end])
01669           pattern = '<%sf'%length
01670           start = end
01671           end += struct.calcsize(pattern)
01672           val3.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
01673           _v99.channels.append(val3)
01674         self.object.models.append(val1)
01675       start = end
01676       end += 4
01677       (length,) = _struct_I.unpack(str[start:end])
01678       self.object.markers.markers = []
01679       for i in range(0, length):
01680         val1 = visualization_msgs.msg.Marker()
01681         _v109 = val1.header
01682         start = end
01683         end += 4
01684         (_v109.seq,) = _struct_I.unpack(str[start:end])
01685         _v110 = _v109.stamp
01686         _x = _v110
01687         start = end
01688         end += 8
01689         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
01690         start = end
01691         end += 4
01692         (length,) = _struct_I.unpack(str[start:end])
01693         start = end
01694         end += length
01695         if python3:
01696           _v109.frame_id = str[start:end].decode('utf-8')
01697         else:
01698           _v109.frame_id = str[start:end]
01699         start = end
01700         end += 4
01701         (length,) = _struct_I.unpack(str[start:end])
01702         start = end
01703         end += length
01704         if python3:
01705           val1.ns = str[start:end].decode('utf-8')
01706         else:
01707           val1.ns = str[start:end]
01708         _x = val1
01709         start = end
01710         end += 12
01711         (_x.id, _x.type, _x.action,) = _struct_3i.unpack(str[start:end])
01712         _v111 = val1.pose
01713         _v112 = _v111.position
01714         _x = _v112
01715         start = end
01716         end += 24
01717         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01718         _v113 = _v111.orientation
01719         _x = _v113
01720         start = end
01721         end += 32
01722         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
01723         _v114 = val1.scale
01724         _x = _v114
01725         start = end
01726         end += 24
01727         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01728         _v115 = val1.color
01729         _x = _v115
01730         start = end
01731         end += 16
01732         (_x.r, _x.g, _x.b, _x.a,) = _struct_4f.unpack(str[start:end])
01733         _v116 = val1.lifetime
01734         _x = _v116
01735         start = end
01736         end += 8
01737         (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
01738         start = end
01739         end += 1
01740         (val1.frame_locked,) = _struct_B.unpack(str[start:end])
01741         val1.frame_locked = bool(val1.frame_locked)
01742         start = end
01743         end += 4
01744         (length,) = _struct_I.unpack(str[start:end])
01745         val1.points = []
01746         for i in range(0, length):
01747           val2 = geometry_msgs.msg.Point()
01748           _x = val2
01749           start = end
01750           end += 24
01751           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
01752           val1.points.append(val2)
01753         start = end
01754         end += 4
01755         (length,) = _struct_I.unpack(str[start:end])
01756         val1.colors = []
01757         for i in range(0, length):
01758           val2 = std_msgs.msg.ColorRGBA()
01759           _x = val2
01760           start = end
01761           end += 16
01762           (_x.r, _x.g, _x.b, _x.a,) = _struct_4f.unpack(str[start:end])
01763           val1.colors.append(val2)
01764         start = end
01765         end += 4
01766         (length,) = _struct_I.unpack(str[start:end])
01767         start = end
01768         end += length
01769         if python3:
01770           val1.text = str[start:end].decode('utf-8')
01771         else:
01772           val1.text = str[start:end]
01773         start = end
01774         end += 4
01775         (length,) = _struct_I.unpack(str[start:end])
01776         start = end
01777         end += length
01778         if python3:
01779           val1.mesh_resource = str[start:end].decode('utf-8')
01780         else:
01781           val1.mesh_resource = str[start:end]
01782         start = end
01783         end += 1
01784         (val1.mesh_use_embedded_materials,) = _struct_B.unpack(str[start:end])
01785         val1.mesh_use_embedded_materials = bool(val1.mesh_use_embedded_materials)
01786         self.object.markers.markers.append(val1)
01787       return self
01788     except struct.error as e:
01789       raise genpy.DeserializationError(e) #most likely buffer underfill
01790 
01791 _struct_I = genpy.struct_I
01792 _struct_B = struct.Struct("<B")
01793 _struct_dB = struct.Struct("<dB")
01794 _struct_3i = struct.Struct("<3i")
01795 _struct_2i = struct.Struct("<2i")
01796 _struct_i = struct.Struct("<i")
01797 _struct_3I = struct.Struct("<3I")
01798 _struct_4f = struct.Struct("<4f")
01799 _struct_4d = struct.Struct("<4d")
01800 _struct_2I = struct.Struct("<2I")
01801 _struct_3d = struct.Struct("<3d")
01802 """autogenerated by genpy from articulation_msgs/ArticulatedObjectSrvResponse.msg. Do not edit."""
01803 import sys
01804 python3 = True if sys.hexversion > 0x03000000 else False
01805 import genpy
01806 import struct
01807 
01808 import visualization_msgs.msg
01809 import articulation_msgs.msg
01810 import geometry_msgs.msg
01811 import sensor_msgs.msg
01812 import genpy
01813 import std_msgs.msg
01814 
01815 class ArticulatedObjectSrvResponse(genpy.Message):
01816   _md5sum = "5d5d9e6b857e5dae46feed46b9a03103"
01817   _type = "articulation_msgs/ArticulatedObjectSrvResponse"
01818   _has_header = False #flag to mark the presence of a Header object
01819   _full_text = """articulation_msgs/ArticulatedObjectMsg object
01820 
01821 
01822 
01823 
01824 
01825 
01826 ================================================================================
01827 MSG: articulation_msgs/ArticulatedObjectMsg
01828 std_msgs/Header header
01829 
01830 articulation_msgs/TrackMsg[] parts    # observed trajectories for each object part 
01831 articulation_msgs/ParamMsg[] params   # global parameters
01832 articulation_msgs/ModelMsg[] models       # models, describing relationships between parts
01833 visualization_msgs/MarkerArray markers # marker visualization of models/object 
01834 
01835 ================================================================================
01836 MSG: std_msgs/Header
01837 # Standard metadata for higher-level stamped data types.
01838 # This is generally used to communicate timestamped data 
01839 # in a particular coordinate frame.
01840 # 
01841 # sequence ID: consecutively increasing ID 
01842 uint32 seq
01843 #Two-integer timestamp that is expressed as:
01844 # * stamp.secs: seconds (stamp_secs) since epoch
01845 # * stamp.nsecs: nanoseconds since stamp_secs
01846 # time-handling sugar is provided by the client library
01847 time stamp
01848 #Frame this data is associated with
01849 # 0: no frame
01850 # 1: global frame
01851 string frame_id
01852 
01853 ================================================================================
01854 MSG: articulation_msgs/TrackMsg
01855 # Single kinematic trajectory
01856 #
01857 # This message contains a kinematic trajectory. The trajectory is specified
01858 # as a vector of 6D poses. An additional flag, track_type, indicates whether
01859 # the track is valid, and whether it includes orientation. The track id
01860 # can be used for automatic coloring in the RVIZ track plugin, and can be 
01861 # freely chosen by the client. 
01862 #
01863 # A model is fitting only from the trajectory stored in the pose[]-vector. 
01864 # Additional information may be associated to each pose using the channels
01865 # vector, with arbitrary # fields (e.g., to include applied/measured forces). 
01866 #
01867 # After model evaluation,
01868 # also the associated configurations of the object are stored in the channels,
01869 # named "q[0]".."q[DOF-1]", where DOF is the number of degrees of freedom.
01870 # Model evaluation also projects the poses in the pose vector onto the model,
01871 # and stores these ideal poses in the vector pose_projected. Further, during model
01872 # evaluation, a new set of (uniform) configurations over the valid configuration
01873 # range is sampled, and the result is stored in pose_resampled.
01874 # The vector pose_flags contains additional display flags for the poses in the
01875 # pose vector, for example, whether a pose is visible and/or
01876 # the end of a trajectory segment. At the moment, this is only used by the
01877 # prior_model_learner.
01878 #
01879 
01880 std_msgs/Header header                        # frame and timestamp
01881 int32 id                                # used-specified track id
01882 
01883 geometry_msgs/Pose[] pose               # sequence of poses, defining the observed trajectory
01884 std_msgs/Header[] pose_headers                   # Timestamp and frame for each pose (and pose_projected)
01885 geometry_msgs/Pose[] pose_projected     # sequence of poses, projected to the model 
01886                                         # (after model evaluation)
01887 geometry_msgs/Pose[] pose_resampled     # sequence of poses, re-sampled from the model in
01888                                         # the valid configuration range
01889 uint32[] pose_flags                     # bit-wise combination of POSE_VISIBLE and POSE_END_OF_SEGMENT
01890 
01891 uint32 POSE_VISIBLE=1
01892 uint32 POSE_END_OF_SEGMENT=2
01893 
01894 # Each channel should have the same number of elements as pose array, 
01895 # and the data in each channel should correspond 1:1 with each pose
01896 # possible channels: "width", "height", "rgb", ...
01897 sensor_msgs/ChannelFloat32[] channels       
01898 
01899 
01900 
01901 ================================================================================
01902 MSG: geometry_msgs/Pose
01903 # A representation of pose in free space, composed of postion and orientation. 
01904 Point position
01905 Quaternion orientation
01906 
01907 ================================================================================
01908 MSG: geometry_msgs/Point
01909 # This contains the position of a point in free space
01910 float64 x
01911 float64 y
01912 float64 z
01913 
01914 ================================================================================
01915 MSG: geometry_msgs/Quaternion
01916 # This represents an orientation in free space in quaternion form.
01917 
01918 float64 x
01919 float64 y
01920 float64 z
01921 float64 w
01922 
01923 ================================================================================
01924 MSG: sensor_msgs/ChannelFloat32
01925 # This message is used by the PointCloud message to hold optional data
01926 # associated with each point in the cloud. The length of the values
01927 # array should be the same as the length of the points array in the
01928 # PointCloud, and each value should be associated with the corresponding
01929 # point.
01930 
01931 # Channel names in existing practice include:
01932 #   "u", "v" - row and column (respectively) in the left stereo image.
01933 #              This is opposite to usual conventions but remains for
01934 #              historical reasons. The newer PointCloud2 message has no
01935 #              such problem.
01936 #   "rgb" - For point clouds produced by color stereo cameras. uint8
01937 #           (R,G,B) values packed into the least significant 24 bits,
01938 #           in order.
01939 #   "intensity" - laser or pixel intensity.
01940 #   "distance"
01941 
01942 # The channel name should give semantics of the channel (e.g.
01943 # "intensity" instead of "value").
01944 string name
01945 
01946 # The values array should be 1-1 with the elements of the associated
01947 # PointCloud.
01948 float32[] values
01949 
01950 ================================================================================
01951 MSG: articulation_msgs/ParamMsg
01952 # Single parameter passed to or from model fitting
01953 #
01954 # This mechanism allows to flexibly pass parameters to 
01955 # model fitting (and vice versa). Note that these parameters 
01956 # are model-specific: A client may supply additional
01957 # parameters to the model estimator, and, similarly, a estimator
01958 # may add the estimated model parameters to the model message.
01959 # When the model is then evaluated, for example to make predictions
01960 # or to compute the likelihood, the model class can then use
01961 # these parameters.
01962 #
01963 # A parameter has a name, a value, and a type. The type globally
01964 # indicates whether it is a prior parameter (prior to model fitting),
01965 # or a model parameter (found during model fitting, using a maximum-
01966 # likelihood estimator), or a cached evaluation (e.g., the likelihood
01967 # or the BIC are a typical "side"-product of model estimation, and
01968 # can therefore already be cached).
01969 #
01970 # For a list of currently used parameters, see the documentation at
01971 # http://www.ros.org/wiki/articulation_models
01972 #
01973 
01974 uint8 PRIOR=0   # indicates a prior model parameter 
01975                 # (e.g., "sigma_position")
01976 uint8 PARAM=1   # indicates a estimated model parameter 
01977                 # (e.g., "rot_radius", the estimated radius)
01978 uint8 EVAL=2    # indicates a cached evaluation of the model, given 
01979                 # the current trajectory
01980                 # (e.g., "loglikelihood", the log likelihood of the
01981                 # data, given the model and its parameters)
01982 
01983 string name     # name of the parameter
01984 float64 value   # value of the parameter
01985 uint8 type      # type of the parameter (PRIOR, PARAM, EVAL)
01986 
01987 
01988 ================================================================================
01989 MSG: articulation_msgs/ModelMsg
01990 # Single kinematic model
01991 #
01992 # A kinematic model is defined by its model class name, and a set of parameters. 
01993 # The client may additionally specify a model id, that can be used to colorize the
01994 # model when visualized using the RVIZ model display.
01995 # 
01996 # For a list of currently implemented models, see the documetation at
01997 # http://www.ros.org/wiki/articulation_models
01998 #
01999 #
02000 
02001 std_msgs/Header header                        # frame and timestamp
02002 
02003 int32 id                             # user specified model id
02004 string name                          # name of the model family (e.g. "rotational",
02005                                      # "prismatic", "pca-gp", "rigid")
02006 articulation_msgs/ParamMsg[] params  # model parameters
02007 articulation_msgs/TrackMsg track     # trajectory from which the model is estimated, or
02008                                      # that is evaluated using the model
02009 
02010 ================================================================================
02011 MSG: visualization_msgs/MarkerArray
02012 Marker[] markers
02013 
02014 ================================================================================
02015 MSG: visualization_msgs/Marker
02016 # See http://www.ros.org/wiki/rviz/DisplayTypes/Marker and http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes for more information on using this message with rviz
02017 
02018 uint8 ARROW=0
02019 uint8 CUBE=1
02020 uint8 SPHERE=2
02021 uint8 CYLINDER=3
02022 uint8 LINE_STRIP=4
02023 uint8 LINE_LIST=5
02024 uint8 CUBE_LIST=6
02025 uint8 SPHERE_LIST=7
02026 uint8 POINTS=8
02027 uint8 TEXT_VIEW_FACING=9
02028 uint8 MESH_RESOURCE=10
02029 uint8 TRIANGLE_LIST=11
02030 
02031 uint8 ADD=0
02032 uint8 MODIFY=0
02033 uint8 DELETE=2
02034 
02035 Header header                        # header for time/frame information
02036 string ns                            # Namespace to place this object in... used in conjunction with id to create a unique name for the object
02037 int32 id                                         # object ID useful in conjunction with the namespace for manipulating and deleting the object later
02038 int32 type                                     # Type of object
02039 int32 action                           # 0 add/modify an object, 1 (deprecated), 2 deletes an object
02040 geometry_msgs/Pose pose                 # Pose of the object
02041 geometry_msgs/Vector3 scale             # Scale of the object 1,1,1 means default (usually 1 meter square)
02042 std_msgs/ColorRGBA color             # Color [0.0-1.0]
02043 duration lifetime                    # How long the object should last before being automatically deleted.  0 means forever
02044 bool frame_locked                    # If this marker should be frame-locked, i.e. retransformed into its frame every timestep
02045 
02046 #Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)
02047 geometry_msgs/Point[] points
02048 #Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...)
02049 #number of colors must either be 0 or equal to the number of points
02050 #NOTE: alpha is not yet used
02051 std_msgs/ColorRGBA[] colors
02052 
02053 # NOTE: only used for text markers
02054 string text
02055 
02056 # NOTE: only used for MESH_RESOURCE markers
02057 string mesh_resource
02058 bool mesh_use_embedded_materials
02059 
02060 ================================================================================
02061 MSG: geometry_msgs/Vector3
02062 # This represents a vector in free space. 
02063 
02064 float64 x
02065 float64 y
02066 float64 z
02067 ================================================================================
02068 MSG: std_msgs/ColorRGBA
02069 float32 r
02070 float32 g
02071 float32 b
02072 float32 a
02073 
02074 """
02075   __slots__ = ['object']
02076   _slot_types = ['articulation_msgs/ArticulatedObjectMsg']
02077 
02078   def __init__(self, *args, **kwds):
02079     """
02080     Constructor. Any message fields that are implicitly/explicitly
02081     set to None will be assigned a default value. The recommend
02082     use is keyword arguments as this is more robust to future message
02083     changes.  You cannot mix in-order arguments and keyword arguments.
02084 
02085     The available fields are:
02086        object
02087 
02088     :param args: complete set of field values, in .msg order
02089     :param kwds: use keyword arguments corresponding to message field names
02090     to set specific fields.
02091     """
02092     if args or kwds:
02093       super(ArticulatedObjectSrvResponse, self).__init__(*args, **kwds)
02094       #message fields cannot be None, assign default values for those that are
02095       if self.object is None:
02096         self.object = articulation_msgs.msg.ArticulatedObjectMsg()
02097     else:
02098       self.object = articulation_msgs.msg.ArticulatedObjectMsg()
02099 
02100   def _get_types(self):
02101     """
02102     internal API method
02103     """
02104     return self._slot_types
02105 
02106   def serialize(self, buff):
02107     """
02108     serialize message into buffer
02109     :param buff: buffer, ``StringIO``
02110     """
02111     try:
02112       _x = self
02113       buff.write(_struct_3I.pack(_x.object.header.seq, _x.object.header.stamp.secs, _x.object.header.stamp.nsecs))
02114       _x = self.object.header.frame_id
02115       length = len(_x)
02116       if python3 or type(_x) == unicode:
02117         _x = _x.encode('utf-8')
02118         length = len(_x)
02119       buff.write(struct.pack('<I%ss'%length, length, _x))
02120       length = len(self.object.parts)
02121       buff.write(_struct_I.pack(length))
02122       for val1 in self.object.parts:
02123         _v117 = val1.header
02124         buff.write(_struct_I.pack(_v117.seq))
02125         _v118 = _v117.stamp
02126         _x = _v118
02127         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02128         _x = _v117.frame_id
02129         length = len(_x)
02130         if python3 or type(_x) == unicode:
02131           _x = _x.encode('utf-8')
02132           length = len(_x)
02133         buff.write(struct.pack('<I%ss'%length, length, _x))
02134         buff.write(_struct_i.pack(val1.id))
02135         length = len(val1.pose)
02136         buff.write(_struct_I.pack(length))
02137         for val2 in val1.pose:
02138           _v119 = val2.position
02139           _x = _v119
02140           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02141           _v120 = val2.orientation
02142           _x = _v120
02143           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02144         length = len(val1.pose_headers)
02145         buff.write(_struct_I.pack(length))
02146         for val2 in val1.pose_headers:
02147           buff.write(_struct_I.pack(val2.seq))
02148           _v121 = val2.stamp
02149           _x = _v121
02150           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02151           _x = val2.frame_id
02152           length = len(_x)
02153           if python3 or type(_x) == unicode:
02154             _x = _x.encode('utf-8')
02155             length = len(_x)
02156           buff.write(struct.pack('<I%ss'%length, length, _x))
02157         length = len(val1.pose_projected)
02158         buff.write(_struct_I.pack(length))
02159         for val2 in val1.pose_projected:
02160           _v122 = val2.position
02161           _x = _v122
02162           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02163           _v123 = val2.orientation
02164           _x = _v123
02165           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02166         length = len(val1.pose_resampled)
02167         buff.write(_struct_I.pack(length))
02168         for val2 in val1.pose_resampled:
02169           _v124 = val2.position
02170           _x = _v124
02171           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02172           _v125 = val2.orientation
02173           _x = _v125
02174           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02175         length = len(val1.pose_flags)
02176         buff.write(_struct_I.pack(length))
02177         pattern = '<%sI'%length
02178         buff.write(struct.pack(pattern, *val1.pose_flags))
02179         length = len(val1.channels)
02180         buff.write(_struct_I.pack(length))
02181         for val2 in val1.channels:
02182           _x = val2.name
02183           length = len(_x)
02184           if python3 or type(_x) == unicode:
02185             _x = _x.encode('utf-8')
02186             length = len(_x)
02187           buff.write(struct.pack('<I%ss'%length, length, _x))
02188           length = len(val2.values)
02189           buff.write(_struct_I.pack(length))
02190           pattern = '<%sf'%length
02191           buff.write(struct.pack(pattern, *val2.values))
02192       length = len(self.object.params)
02193       buff.write(_struct_I.pack(length))
02194       for val1 in self.object.params:
02195         _x = val1.name
02196         length = len(_x)
02197         if python3 or type(_x) == unicode:
02198           _x = _x.encode('utf-8')
02199           length = len(_x)
02200         buff.write(struct.pack('<I%ss'%length, length, _x))
02201         _x = val1
02202         buff.write(_struct_dB.pack(_x.value, _x.type))
02203       length = len(self.object.models)
02204       buff.write(_struct_I.pack(length))
02205       for val1 in self.object.models:
02206         _v126 = val1.header
02207         buff.write(_struct_I.pack(_v126.seq))
02208         _v127 = _v126.stamp
02209         _x = _v127
02210         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02211         _x = _v126.frame_id
02212         length = len(_x)
02213         if python3 or type(_x) == unicode:
02214           _x = _x.encode('utf-8')
02215           length = len(_x)
02216         buff.write(struct.pack('<I%ss'%length, length, _x))
02217         buff.write(_struct_i.pack(val1.id))
02218         _x = val1.name
02219         length = len(_x)
02220         if python3 or type(_x) == unicode:
02221           _x = _x.encode('utf-8')
02222           length = len(_x)
02223         buff.write(struct.pack('<I%ss'%length, length, _x))
02224         length = len(val1.params)
02225         buff.write(_struct_I.pack(length))
02226         for val2 in val1.params:
02227           _x = val2.name
02228           length = len(_x)
02229           if python3 or type(_x) == unicode:
02230             _x = _x.encode('utf-8')
02231             length = len(_x)
02232           buff.write(struct.pack('<I%ss'%length, length, _x))
02233           _x = val2
02234           buff.write(_struct_dB.pack(_x.value, _x.type))
02235         _v128 = val1.track
02236         _v129 = _v128.header
02237         buff.write(_struct_I.pack(_v129.seq))
02238         _v130 = _v129.stamp
02239         _x = _v130
02240         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02241         _x = _v129.frame_id
02242         length = len(_x)
02243         if python3 or type(_x) == unicode:
02244           _x = _x.encode('utf-8')
02245           length = len(_x)
02246         buff.write(struct.pack('<I%ss'%length, length, _x))
02247         buff.write(_struct_i.pack(_v128.id))
02248         length = len(_v128.pose)
02249         buff.write(_struct_I.pack(length))
02250         for val3 in _v128.pose:
02251           _v131 = val3.position
02252           _x = _v131
02253           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02254           _v132 = val3.orientation
02255           _x = _v132
02256           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02257         length = len(_v128.pose_headers)
02258         buff.write(_struct_I.pack(length))
02259         for val3 in _v128.pose_headers:
02260           buff.write(_struct_I.pack(val3.seq))
02261           _v133 = val3.stamp
02262           _x = _v133
02263           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02264           _x = val3.frame_id
02265           length = len(_x)
02266           if python3 or type(_x) == unicode:
02267             _x = _x.encode('utf-8')
02268             length = len(_x)
02269           buff.write(struct.pack('<I%ss'%length, length, _x))
02270         length = len(_v128.pose_projected)
02271         buff.write(_struct_I.pack(length))
02272         for val3 in _v128.pose_projected:
02273           _v134 = val3.position
02274           _x = _v134
02275           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02276           _v135 = val3.orientation
02277           _x = _v135
02278           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02279         length = len(_v128.pose_resampled)
02280         buff.write(_struct_I.pack(length))
02281         for val3 in _v128.pose_resampled:
02282           _v136 = val3.position
02283           _x = _v136
02284           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02285           _v137 = val3.orientation
02286           _x = _v137
02287           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02288         length = len(_v128.pose_flags)
02289         buff.write(_struct_I.pack(length))
02290         pattern = '<%sI'%length
02291         buff.write(struct.pack(pattern, *_v128.pose_flags))
02292         length = len(_v128.channels)
02293         buff.write(_struct_I.pack(length))
02294         for val3 in _v128.channels:
02295           _x = val3.name
02296           length = len(_x)
02297           if python3 or type(_x) == unicode:
02298             _x = _x.encode('utf-8')
02299             length = len(_x)
02300           buff.write(struct.pack('<I%ss'%length, length, _x))
02301           length = len(val3.values)
02302           buff.write(_struct_I.pack(length))
02303           pattern = '<%sf'%length
02304           buff.write(struct.pack(pattern, *val3.values))
02305       length = len(self.object.markers.markers)
02306       buff.write(_struct_I.pack(length))
02307       for val1 in self.object.markers.markers:
02308         _v138 = val1.header
02309         buff.write(_struct_I.pack(_v138.seq))
02310         _v139 = _v138.stamp
02311         _x = _v139
02312         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02313         _x = _v138.frame_id
02314         length = len(_x)
02315         if python3 or type(_x) == unicode:
02316           _x = _x.encode('utf-8')
02317           length = len(_x)
02318         buff.write(struct.pack('<I%ss'%length, length, _x))
02319         _x = val1.ns
02320         length = len(_x)
02321         if python3 or type(_x) == unicode:
02322           _x = _x.encode('utf-8')
02323           length = len(_x)
02324         buff.write(struct.pack('<I%ss'%length, length, _x))
02325         _x = val1
02326         buff.write(_struct_3i.pack(_x.id, _x.type, _x.action))
02327         _v140 = val1.pose
02328         _v141 = _v140.position
02329         _x = _v141
02330         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02331         _v142 = _v140.orientation
02332         _x = _v142
02333         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02334         _v143 = val1.scale
02335         _x = _v143
02336         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02337         _v144 = val1.color
02338         _x = _v144
02339         buff.write(_struct_4f.pack(_x.r, _x.g, _x.b, _x.a))
02340         _v145 = val1.lifetime
02341         _x = _v145
02342         buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
02343         buff.write(_struct_B.pack(val1.frame_locked))
02344         length = len(val1.points)
02345         buff.write(_struct_I.pack(length))
02346         for val2 in val1.points:
02347           _x = val2
02348           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02349         length = len(val1.colors)
02350         buff.write(_struct_I.pack(length))
02351         for val2 in val1.colors:
02352           _x = val2
02353           buff.write(_struct_4f.pack(_x.r, _x.g, _x.b, _x.a))
02354         _x = val1.text
02355         length = len(_x)
02356         if python3 or type(_x) == unicode:
02357           _x = _x.encode('utf-8')
02358           length = len(_x)
02359         buff.write(struct.pack('<I%ss'%length, length, _x))
02360         _x = val1.mesh_resource
02361         length = len(_x)
02362         if python3 or type(_x) == unicode:
02363           _x = _x.encode('utf-8')
02364           length = len(_x)
02365         buff.write(struct.pack('<I%ss'%length, length, _x))
02366         buff.write(_struct_B.pack(val1.mesh_use_embedded_materials))
02367     except struct.error as se: self._check_types(se)
02368     except TypeError as te: self._check_types(te)
02369 
02370   def deserialize(self, str):
02371     """
02372     unpack serialized message in str into this message instance
02373     :param str: byte array of serialized message, ``str``
02374     """
02375     try:
02376       if self.object is None:
02377         self.object = articulation_msgs.msg.ArticulatedObjectMsg()
02378       end = 0
02379       _x = self
02380       start = end
02381       end += 12
02382       (_x.object.header.seq, _x.object.header.stamp.secs, _x.object.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
02383       start = end
02384       end += 4
02385       (length,) = _struct_I.unpack(str[start:end])
02386       start = end
02387       end += length
02388       if python3:
02389         self.object.header.frame_id = str[start:end].decode('utf-8')
02390       else:
02391         self.object.header.frame_id = str[start:end]
02392       start = end
02393       end += 4
02394       (length,) = _struct_I.unpack(str[start:end])
02395       self.object.parts = []
02396       for i in range(0, length):
02397         val1 = articulation_msgs.msg.TrackMsg()
02398         _v146 = val1.header
02399         start = end
02400         end += 4
02401         (_v146.seq,) = _struct_I.unpack(str[start:end])
02402         _v147 = _v146.stamp
02403         _x = _v147
02404         start = end
02405         end += 8
02406         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02407         start = end
02408         end += 4
02409         (length,) = _struct_I.unpack(str[start:end])
02410         start = end
02411         end += length
02412         if python3:
02413           _v146.frame_id = str[start:end].decode('utf-8')
02414         else:
02415           _v146.frame_id = str[start:end]
02416         start = end
02417         end += 4
02418         (val1.id,) = _struct_i.unpack(str[start:end])
02419         start = end
02420         end += 4
02421         (length,) = _struct_I.unpack(str[start:end])
02422         val1.pose = []
02423         for i in range(0, length):
02424           val2 = geometry_msgs.msg.Pose()
02425           _v148 = val2.position
02426           _x = _v148
02427           start = end
02428           end += 24
02429           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02430           _v149 = val2.orientation
02431           _x = _v149
02432           start = end
02433           end += 32
02434           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02435           val1.pose.append(val2)
02436         start = end
02437         end += 4
02438         (length,) = _struct_I.unpack(str[start:end])
02439         val1.pose_headers = []
02440         for i in range(0, length):
02441           val2 = std_msgs.msg.Header()
02442           start = end
02443           end += 4
02444           (val2.seq,) = _struct_I.unpack(str[start:end])
02445           _v150 = val2.stamp
02446           _x = _v150
02447           start = end
02448           end += 8
02449           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02450           start = end
02451           end += 4
02452           (length,) = _struct_I.unpack(str[start:end])
02453           start = end
02454           end += length
02455           if python3:
02456             val2.frame_id = str[start:end].decode('utf-8')
02457           else:
02458             val2.frame_id = str[start:end]
02459           val1.pose_headers.append(val2)
02460         start = end
02461         end += 4
02462         (length,) = _struct_I.unpack(str[start:end])
02463         val1.pose_projected = []
02464         for i in range(0, length):
02465           val2 = geometry_msgs.msg.Pose()
02466           _v151 = val2.position
02467           _x = _v151
02468           start = end
02469           end += 24
02470           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02471           _v152 = val2.orientation
02472           _x = _v152
02473           start = end
02474           end += 32
02475           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02476           val1.pose_projected.append(val2)
02477         start = end
02478         end += 4
02479         (length,) = _struct_I.unpack(str[start:end])
02480         val1.pose_resampled = []
02481         for i in range(0, length):
02482           val2 = geometry_msgs.msg.Pose()
02483           _v153 = val2.position
02484           _x = _v153
02485           start = end
02486           end += 24
02487           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02488           _v154 = val2.orientation
02489           _x = _v154
02490           start = end
02491           end += 32
02492           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02493           val1.pose_resampled.append(val2)
02494         start = end
02495         end += 4
02496         (length,) = _struct_I.unpack(str[start:end])
02497         pattern = '<%sI'%length
02498         start = end
02499         end += struct.calcsize(pattern)
02500         val1.pose_flags = struct.unpack(pattern, str[start:end])
02501         start = end
02502         end += 4
02503         (length,) = _struct_I.unpack(str[start:end])
02504         val1.channels = []
02505         for i in range(0, length):
02506           val2 = sensor_msgs.msg.ChannelFloat32()
02507           start = end
02508           end += 4
02509           (length,) = _struct_I.unpack(str[start:end])
02510           start = end
02511           end += length
02512           if python3:
02513             val2.name = str[start:end].decode('utf-8')
02514           else:
02515             val2.name = str[start:end]
02516           start = end
02517           end += 4
02518           (length,) = _struct_I.unpack(str[start:end])
02519           pattern = '<%sf'%length
02520           start = end
02521           end += struct.calcsize(pattern)
02522           val2.values = struct.unpack(pattern, str[start:end])
02523           val1.channels.append(val2)
02524         self.object.parts.append(val1)
02525       start = end
02526       end += 4
02527       (length,) = _struct_I.unpack(str[start:end])
02528       self.object.params = []
02529       for i in range(0, length):
02530         val1 = articulation_msgs.msg.ParamMsg()
02531         start = end
02532         end += 4
02533         (length,) = _struct_I.unpack(str[start:end])
02534         start = end
02535         end += length
02536         if python3:
02537           val1.name = str[start:end].decode('utf-8')
02538         else:
02539           val1.name = str[start:end]
02540         _x = val1
02541         start = end
02542         end += 9
02543         (_x.value, _x.type,) = _struct_dB.unpack(str[start:end])
02544         self.object.params.append(val1)
02545       start = end
02546       end += 4
02547       (length,) = _struct_I.unpack(str[start:end])
02548       self.object.models = []
02549       for i in range(0, length):
02550         val1 = articulation_msgs.msg.ModelMsg()
02551         _v155 = val1.header
02552         start = end
02553         end += 4
02554         (_v155.seq,) = _struct_I.unpack(str[start:end])
02555         _v156 = _v155.stamp
02556         _x = _v156
02557         start = end
02558         end += 8
02559         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02560         start = end
02561         end += 4
02562         (length,) = _struct_I.unpack(str[start:end])
02563         start = end
02564         end += length
02565         if python3:
02566           _v155.frame_id = str[start:end].decode('utf-8')
02567         else:
02568           _v155.frame_id = str[start:end]
02569         start = end
02570         end += 4
02571         (val1.id,) = _struct_i.unpack(str[start:end])
02572         start = end
02573         end += 4
02574         (length,) = _struct_I.unpack(str[start:end])
02575         start = end
02576         end += length
02577         if python3:
02578           val1.name = str[start:end].decode('utf-8')
02579         else:
02580           val1.name = str[start:end]
02581         start = end
02582         end += 4
02583         (length,) = _struct_I.unpack(str[start:end])
02584         val1.params = []
02585         for i in range(0, length):
02586           val2 = articulation_msgs.msg.ParamMsg()
02587           start = end
02588           end += 4
02589           (length,) = _struct_I.unpack(str[start:end])
02590           start = end
02591           end += length
02592           if python3:
02593             val2.name = str[start:end].decode('utf-8')
02594           else:
02595             val2.name = str[start:end]
02596           _x = val2
02597           start = end
02598           end += 9
02599           (_x.value, _x.type,) = _struct_dB.unpack(str[start:end])
02600           val1.params.append(val2)
02601         _v157 = val1.track
02602         _v158 = _v157.header
02603         start = end
02604         end += 4
02605         (_v158.seq,) = _struct_I.unpack(str[start:end])
02606         _v159 = _v158.stamp
02607         _x = _v159
02608         start = end
02609         end += 8
02610         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02611         start = end
02612         end += 4
02613         (length,) = _struct_I.unpack(str[start:end])
02614         start = end
02615         end += length
02616         if python3:
02617           _v158.frame_id = str[start:end].decode('utf-8')
02618         else:
02619           _v158.frame_id = str[start:end]
02620         start = end
02621         end += 4
02622         (_v157.id,) = _struct_i.unpack(str[start:end])
02623         start = end
02624         end += 4
02625         (length,) = _struct_I.unpack(str[start:end])
02626         _v157.pose = []
02627         for i in range(0, length):
02628           val3 = geometry_msgs.msg.Pose()
02629           _v160 = val3.position
02630           _x = _v160
02631           start = end
02632           end += 24
02633           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02634           _v161 = val3.orientation
02635           _x = _v161
02636           start = end
02637           end += 32
02638           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02639           _v157.pose.append(val3)
02640         start = end
02641         end += 4
02642         (length,) = _struct_I.unpack(str[start:end])
02643         _v157.pose_headers = []
02644         for i in range(0, length):
02645           val3 = std_msgs.msg.Header()
02646           start = end
02647           end += 4
02648           (val3.seq,) = _struct_I.unpack(str[start:end])
02649           _v162 = val3.stamp
02650           _x = _v162
02651           start = end
02652           end += 8
02653           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02654           start = end
02655           end += 4
02656           (length,) = _struct_I.unpack(str[start:end])
02657           start = end
02658           end += length
02659           if python3:
02660             val3.frame_id = str[start:end].decode('utf-8')
02661           else:
02662             val3.frame_id = str[start:end]
02663           _v157.pose_headers.append(val3)
02664         start = end
02665         end += 4
02666         (length,) = _struct_I.unpack(str[start:end])
02667         _v157.pose_projected = []
02668         for i in range(0, length):
02669           val3 = geometry_msgs.msg.Pose()
02670           _v163 = val3.position
02671           _x = _v163
02672           start = end
02673           end += 24
02674           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02675           _v164 = val3.orientation
02676           _x = _v164
02677           start = end
02678           end += 32
02679           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02680           _v157.pose_projected.append(val3)
02681         start = end
02682         end += 4
02683         (length,) = _struct_I.unpack(str[start:end])
02684         _v157.pose_resampled = []
02685         for i in range(0, length):
02686           val3 = geometry_msgs.msg.Pose()
02687           _v165 = val3.position
02688           _x = _v165
02689           start = end
02690           end += 24
02691           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02692           _v166 = val3.orientation
02693           _x = _v166
02694           start = end
02695           end += 32
02696           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02697           _v157.pose_resampled.append(val3)
02698         start = end
02699         end += 4
02700         (length,) = _struct_I.unpack(str[start:end])
02701         pattern = '<%sI'%length
02702         start = end
02703         end += struct.calcsize(pattern)
02704         _v157.pose_flags = struct.unpack(pattern, str[start:end])
02705         start = end
02706         end += 4
02707         (length,) = _struct_I.unpack(str[start:end])
02708         _v157.channels = []
02709         for i in range(0, length):
02710           val3 = sensor_msgs.msg.ChannelFloat32()
02711           start = end
02712           end += 4
02713           (length,) = _struct_I.unpack(str[start:end])
02714           start = end
02715           end += length
02716           if python3:
02717             val3.name = str[start:end].decode('utf-8')
02718           else:
02719             val3.name = str[start:end]
02720           start = end
02721           end += 4
02722           (length,) = _struct_I.unpack(str[start:end])
02723           pattern = '<%sf'%length
02724           start = end
02725           end += struct.calcsize(pattern)
02726           val3.values = struct.unpack(pattern, str[start:end])
02727           _v157.channels.append(val3)
02728         self.object.models.append(val1)
02729       start = end
02730       end += 4
02731       (length,) = _struct_I.unpack(str[start:end])
02732       self.object.markers.markers = []
02733       for i in range(0, length):
02734         val1 = visualization_msgs.msg.Marker()
02735         _v167 = val1.header
02736         start = end
02737         end += 4
02738         (_v167.seq,) = _struct_I.unpack(str[start:end])
02739         _v168 = _v167.stamp
02740         _x = _v168
02741         start = end
02742         end += 8
02743         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
02744         start = end
02745         end += 4
02746         (length,) = _struct_I.unpack(str[start:end])
02747         start = end
02748         end += length
02749         if python3:
02750           _v167.frame_id = str[start:end].decode('utf-8')
02751         else:
02752           _v167.frame_id = str[start:end]
02753         start = end
02754         end += 4
02755         (length,) = _struct_I.unpack(str[start:end])
02756         start = end
02757         end += length
02758         if python3:
02759           val1.ns = str[start:end].decode('utf-8')
02760         else:
02761           val1.ns = str[start:end]
02762         _x = val1
02763         start = end
02764         end += 12
02765         (_x.id, _x.type, _x.action,) = _struct_3i.unpack(str[start:end])
02766         _v169 = val1.pose
02767         _v170 = _v169.position
02768         _x = _v170
02769         start = end
02770         end += 24
02771         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02772         _v171 = _v169.orientation
02773         _x = _v171
02774         start = end
02775         end += 32
02776         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
02777         _v172 = val1.scale
02778         _x = _v172
02779         start = end
02780         end += 24
02781         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02782         _v173 = val1.color
02783         _x = _v173
02784         start = end
02785         end += 16
02786         (_x.r, _x.g, _x.b, _x.a,) = _struct_4f.unpack(str[start:end])
02787         _v174 = val1.lifetime
02788         _x = _v174
02789         start = end
02790         end += 8
02791         (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
02792         start = end
02793         end += 1
02794         (val1.frame_locked,) = _struct_B.unpack(str[start:end])
02795         val1.frame_locked = bool(val1.frame_locked)
02796         start = end
02797         end += 4
02798         (length,) = _struct_I.unpack(str[start:end])
02799         val1.points = []
02800         for i in range(0, length):
02801           val2 = geometry_msgs.msg.Point()
02802           _x = val2
02803           start = end
02804           end += 24
02805           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
02806           val1.points.append(val2)
02807         start = end
02808         end += 4
02809         (length,) = _struct_I.unpack(str[start:end])
02810         val1.colors = []
02811         for i in range(0, length):
02812           val2 = std_msgs.msg.ColorRGBA()
02813           _x = val2
02814           start = end
02815           end += 16
02816           (_x.r, _x.g, _x.b, _x.a,) = _struct_4f.unpack(str[start:end])
02817           val1.colors.append(val2)
02818         start = end
02819         end += 4
02820         (length,) = _struct_I.unpack(str[start:end])
02821         start = end
02822         end += length
02823         if python3:
02824           val1.text = str[start:end].decode('utf-8')
02825         else:
02826           val1.text = str[start:end]
02827         start = end
02828         end += 4
02829         (length,) = _struct_I.unpack(str[start:end])
02830         start = end
02831         end += length
02832         if python3:
02833           val1.mesh_resource = str[start:end].decode('utf-8')
02834         else:
02835           val1.mesh_resource = str[start:end]
02836         start = end
02837         end += 1
02838         (val1.mesh_use_embedded_materials,) = _struct_B.unpack(str[start:end])
02839         val1.mesh_use_embedded_materials = bool(val1.mesh_use_embedded_materials)
02840         self.object.markers.markers.append(val1)
02841       return self
02842     except struct.error as e:
02843       raise genpy.DeserializationError(e) #most likely buffer underfill
02844 
02845 
02846   def serialize_numpy(self, buff, numpy):
02847     """
02848     serialize message with numpy array types into buffer
02849     :param buff: buffer, ``StringIO``
02850     :param numpy: numpy python module
02851     """
02852     try:
02853       _x = self
02854       buff.write(_struct_3I.pack(_x.object.header.seq, _x.object.header.stamp.secs, _x.object.header.stamp.nsecs))
02855       _x = self.object.header.frame_id
02856       length = len(_x)
02857       if python3 or type(_x) == unicode:
02858         _x = _x.encode('utf-8')
02859         length = len(_x)
02860       buff.write(struct.pack('<I%ss'%length, length, _x))
02861       length = len(self.object.parts)
02862       buff.write(_struct_I.pack(length))
02863       for val1 in self.object.parts:
02864         _v175 = val1.header
02865         buff.write(_struct_I.pack(_v175.seq))
02866         _v176 = _v175.stamp
02867         _x = _v176
02868         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02869         _x = _v175.frame_id
02870         length = len(_x)
02871         if python3 or type(_x) == unicode:
02872           _x = _x.encode('utf-8')
02873           length = len(_x)
02874         buff.write(struct.pack('<I%ss'%length, length, _x))
02875         buff.write(_struct_i.pack(val1.id))
02876         length = len(val1.pose)
02877         buff.write(_struct_I.pack(length))
02878         for val2 in val1.pose:
02879           _v177 = val2.position
02880           _x = _v177
02881           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02882           _v178 = val2.orientation
02883           _x = _v178
02884           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02885         length = len(val1.pose_headers)
02886         buff.write(_struct_I.pack(length))
02887         for val2 in val1.pose_headers:
02888           buff.write(_struct_I.pack(val2.seq))
02889           _v179 = val2.stamp
02890           _x = _v179
02891           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02892           _x = val2.frame_id
02893           length = len(_x)
02894           if python3 or type(_x) == unicode:
02895             _x = _x.encode('utf-8')
02896             length = len(_x)
02897           buff.write(struct.pack('<I%ss'%length, length, _x))
02898         length = len(val1.pose_projected)
02899         buff.write(_struct_I.pack(length))
02900         for val2 in val1.pose_projected:
02901           _v180 = val2.position
02902           _x = _v180
02903           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02904           _v181 = val2.orientation
02905           _x = _v181
02906           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02907         length = len(val1.pose_resampled)
02908         buff.write(_struct_I.pack(length))
02909         for val2 in val1.pose_resampled:
02910           _v182 = val2.position
02911           _x = _v182
02912           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02913           _v183 = val2.orientation
02914           _x = _v183
02915           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02916         length = len(val1.pose_flags)
02917         buff.write(_struct_I.pack(length))
02918         pattern = '<%sI'%length
02919         buff.write(val1.pose_flags.tostring())
02920         length = len(val1.channels)
02921         buff.write(_struct_I.pack(length))
02922         for val2 in val1.channels:
02923           _x = val2.name
02924           length = len(_x)
02925           if python3 or type(_x) == unicode:
02926             _x = _x.encode('utf-8')
02927             length = len(_x)
02928           buff.write(struct.pack('<I%ss'%length, length, _x))
02929           length = len(val2.values)
02930           buff.write(_struct_I.pack(length))
02931           pattern = '<%sf'%length
02932           buff.write(val2.values.tostring())
02933       length = len(self.object.params)
02934       buff.write(_struct_I.pack(length))
02935       for val1 in self.object.params:
02936         _x = val1.name
02937         length = len(_x)
02938         if python3 or type(_x) == unicode:
02939           _x = _x.encode('utf-8')
02940           length = len(_x)
02941         buff.write(struct.pack('<I%ss'%length, length, _x))
02942         _x = val1
02943         buff.write(_struct_dB.pack(_x.value, _x.type))
02944       length = len(self.object.models)
02945       buff.write(_struct_I.pack(length))
02946       for val1 in self.object.models:
02947         _v184 = val1.header
02948         buff.write(_struct_I.pack(_v184.seq))
02949         _v185 = _v184.stamp
02950         _x = _v185
02951         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02952         _x = _v184.frame_id
02953         length = len(_x)
02954         if python3 or type(_x) == unicode:
02955           _x = _x.encode('utf-8')
02956           length = len(_x)
02957         buff.write(struct.pack('<I%ss'%length, length, _x))
02958         buff.write(_struct_i.pack(val1.id))
02959         _x = val1.name
02960         length = len(_x)
02961         if python3 or type(_x) == unicode:
02962           _x = _x.encode('utf-8')
02963           length = len(_x)
02964         buff.write(struct.pack('<I%ss'%length, length, _x))
02965         length = len(val1.params)
02966         buff.write(_struct_I.pack(length))
02967         for val2 in val1.params:
02968           _x = val2.name
02969           length = len(_x)
02970           if python3 or type(_x) == unicode:
02971             _x = _x.encode('utf-8')
02972             length = len(_x)
02973           buff.write(struct.pack('<I%ss'%length, length, _x))
02974           _x = val2
02975           buff.write(_struct_dB.pack(_x.value, _x.type))
02976         _v186 = val1.track
02977         _v187 = _v186.header
02978         buff.write(_struct_I.pack(_v187.seq))
02979         _v188 = _v187.stamp
02980         _x = _v188
02981         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
02982         _x = _v187.frame_id
02983         length = len(_x)
02984         if python3 or type(_x) == unicode:
02985           _x = _x.encode('utf-8')
02986           length = len(_x)
02987         buff.write(struct.pack('<I%ss'%length, length, _x))
02988         buff.write(_struct_i.pack(_v186.id))
02989         length = len(_v186.pose)
02990         buff.write(_struct_I.pack(length))
02991         for val3 in _v186.pose:
02992           _v189 = val3.position
02993           _x = _v189
02994           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
02995           _v190 = val3.orientation
02996           _x = _v190
02997           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
02998         length = len(_v186.pose_headers)
02999         buff.write(_struct_I.pack(length))
03000         for val3 in _v186.pose_headers:
03001           buff.write(_struct_I.pack(val3.seq))
03002           _v191 = val3.stamp
03003           _x = _v191
03004           buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
03005           _x = val3.frame_id
03006           length = len(_x)
03007           if python3 or type(_x) == unicode:
03008             _x = _x.encode('utf-8')
03009             length = len(_x)
03010           buff.write(struct.pack('<I%ss'%length, length, _x))
03011         length = len(_v186.pose_projected)
03012         buff.write(_struct_I.pack(length))
03013         for val3 in _v186.pose_projected:
03014           _v192 = val3.position
03015           _x = _v192
03016           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03017           _v193 = val3.orientation
03018           _x = _v193
03019           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
03020         length = len(_v186.pose_resampled)
03021         buff.write(_struct_I.pack(length))
03022         for val3 in _v186.pose_resampled:
03023           _v194 = val3.position
03024           _x = _v194
03025           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03026           _v195 = val3.orientation
03027           _x = _v195
03028           buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
03029         length = len(_v186.pose_flags)
03030         buff.write(_struct_I.pack(length))
03031         pattern = '<%sI'%length
03032         buff.write(_v186.pose_flags.tostring())
03033         length = len(_v186.channels)
03034         buff.write(_struct_I.pack(length))
03035         for val3 in _v186.channels:
03036           _x = val3.name
03037           length = len(_x)
03038           if python3 or type(_x) == unicode:
03039             _x = _x.encode('utf-8')
03040             length = len(_x)
03041           buff.write(struct.pack('<I%ss'%length, length, _x))
03042           length = len(val3.values)
03043           buff.write(_struct_I.pack(length))
03044           pattern = '<%sf'%length
03045           buff.write(val3.values.tostring())
03046       length = len(self.object.markers.markers)
03047       buff.write(_struct_I.pack(length))
03048       for val1 in self.object.markers.markers:
03049         _v196 = val1.header
03050         buff.write(_struct_I.pack(_v196.seq))
03051         _v197 = _v196.stamp
03052         _x = _v197
03053         buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
03054         _x = _v196.frame_id
03055         length = len(_x)
03056         if python3 or type(_x) == unicode:
03057           _x = _x.encode('utf-8')
03058           length = len(_x)
03059         buff.write(struct.pack('<I%ss'%length, length, _x))
03060         _x = val1.ns
03061         length = len(_x)
03062         if python3 or type(_x) == unicode:
03063           _x = _x.encode('utf-8')
03064           length = len(_x)
03065         buff.write(struct.pack('<I%ss'%length, length, _x))
03066         _x = val1
03067         buff.write(_struct_3i.pack(_x.id, _x.type, _x.action))
03068         _v198 = val1.pose
03069         _v199 = _v198.position
03070         _x = _v199
03071         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03072         _v200 = _v198.orientation
03073         _x = _v200
03074         buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
03075         _v201 = val1.scale
03076         _x = _v201
03077         buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03078         _v202 = val1.color
03079         _x = _v202
03080         buff.write(_struct_4f.pack(_x.r, _x.g, _x.b, _x.a))
03081         _v203 = val1.lifetime
03082         _x = _v203
03083         buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
03084         buff.write(_struct_B.pack(val1.frame_locked))
03085         length = len(val1.points)
03086         buff.write(_struct_I.pack(length))
03087         for val2 in val1.points:
03088           _x = val2
03089           buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
03090         length = len(val1.colors)
03091         buff.write(_struct_I.pack(length))
03092         for val2 in val1.colors:
03093           _x = val2
03094           buff.write(_struct_4f.pack(_x.r, _x.g, _x.b, _x.a))
03095         _x = val1.text
03096         length = len(_x)
03097         if python3 or type(_x) == unicode:
03098           _x = _x.encode('utf-8')
03099           length = len(_x)
03100         buff.write(struct.pack('<I%ss'%length, length, _x))
03101         _x = val1.mesh_resource
03102         length = len(_x)
03103         if python3 or type(_x) == unicode:
03104           _x = _x.encode('utf-8')
03105           length = len(_x)
03106         buff.write(struct.pack('<I%ss'%length, length, _x))
03107         buff.write(_struct_B.pack(val1.mesh_use_embedded_materials))
03108     except struct.error as se: self._check_types(se)
03109     except TypeError as te: self._check_types(te)
03110 
03111   def deserialize_numpy(self, str, numpy):
03112     """
03113     unpack serialized message in str into this message instance using numpy for array types
03114     :param str: byte array of serialized message, ``str``
03115     :param numpy: numpy python module
03116     """
03117     try:
03118       if self.object is None:
03119         self.object = articulation_msgs.msg.ArticulatedObjectMsg()
03120       end = 0
03121       _x = self
03122       start = end
03123       end += 12
03124       (_x.object.header.seq, _x.object.header.stamp.secs, _x.object.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
03125       start = end
03126       end += 4
03127       (length,) = _struct_I.unpack(str[start:end])
03128       start = end
03129       end += length
03130       if python3:
03131         self.object.header.frame_id = str[start:end].decode('utf-8')
03132       else:
03133         self.object.header.frame_id = str[start:end]
03134       start = end
03135       end += 4
03136       (length,) = _struct_I.unpack(str[start:end])
03137       self.object.parts = []
03138       for i in range(0, length):
03139         val1 = articulation_msgs.msg.TrackMsg()
03140         _v204 = val1.header
03141         start = end
03142         end += 4
03143         (_v204.seq,) = _struct_I.unpack(str[start:end])
03144         _v205 = _v204.stamp
03145         _x = _v205
03146         start = end
03147         end += 8
03148         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03149         start = end
03150         end += 4
03151         (length,) = _struct_I.unpack(str[start:end])
03152         start = end
03153         end += length
03154         if python3:
03155           _v204.frame_id = str[start:end].decode('utf-8')
03156         else:
03157           _v204.frame_id = str[start:end]
03158         start = end
03159         end += 4
03160         (val1.id,) = _struct_i.unpack(str[start:end])
03161         start = end
03162         end += 4
03163         (length,) = _struct_I.unpack(str[start:end])
03164         val1.pose = []
03165         for i in range(0, length):
03166           val2 = geometry_msgs.msg.Pose()
03167           _v206 = val2.position
03168           _x = _v206
03169           start = end
03170           end += 24
03171           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03172           _v207 = val2.orientation
03173           _x = _v207
03174           start = end
03175           end += 32
03176           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03177           val1.pose.append(val2)
03178         start = end
03179         end += 4
03180         (length,) = _struct_I.unpack(str[start:end])
03181         val1.pose_headers = []
03182         for i in range(0, length):
03183           val2 = std_msgs.msg.Header()
03184           start = end
03185           end += 4
03186           (val2.seq,) = _struct_I.unpack(str[start:end])
03187           _v208 = val2.stamp
03188           _x = _v208
03189           start = end
03190           end += 8
03191           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03192           start = end
03193           end += 4
03194           (length,) = _struct_I.unpack(str[start:end])
03195           start = end
03196           end += length
03197           if python3:
03198             val2.frame_id = str[start:end].decode('utf-8')
03199           else:
03200             val2.frame_id = str[start:end]
03201           val1.pose_headers.append(val2)
03202         start = end
03203         end += 4
03204         (length,) = _struct_I.unpack(str[start:end])
03205         val1.pose_projected = []
03206         for i in range(0, length):
03207           val2 = geometry_msgs.msg.Pose()
03208           _v209 = val2.position
03209           _x = _v209
03210           start = end
03211           end += 24
03212           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03213           _v210 = val2.orientation
03214           _x = _v210
03215           start = end
03216           end += 32
03217           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03218           val1.pose_projected.append(val2)
03219         start = end
03220         end += 4
03221         (length,) = _struct_I.unpack(str[start:end])
03222         val1.pose_resampled = []
03223         for i in range(0, length):
03224           val2 = geometry_msgs.msg.Pose()
03225           _v211 = val2.position
03226           _x = _v211
03227           start = end
03228           end += 24
03229           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03230           _v212 = val2.orientation
03231           _x = _v212
03232           start = end
03233           end += 32
03234           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03235           val1.pose_resampled.append(val2)
03236         start = end
03237         end += 4
03238         (length,) = _struct_I.unpack(str[start:end])
03239         pattern = '<%sI'%length
03240         start = end
03241         end += struct.calcsize(pattern)
03242         val1.pose_flags = numpy.frombuffer(str[start:end], dtype=numpy.uint32, count=length)
03243         start = end
03244         end += 4
03245         (length,) = _struct_I.unpack(str[start:end])
03246         val1.channels = []
03247         for i in range(0, length):
03248           val2 = sensor_msgs.msg.ChannelFloat32()
03249           start = end
03250           end += 4
03251           (length,) = _struct_I.unpack(str[start:end])
03252           start = end
03253           end += length
03254           if python3:
03255             val2.name = str[start:end].decode('utf-8')
03256           else:
03257             val2.name = str[start:end]
03258           start = end
03259           end += 4
03260           (length,) = _struct_I.unpack(str[start:end])
03261           pattern = '<%sf'%length
03262           start = end
03263           end += struct.calcsize(pattern)
03264           val2.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
03265           val1.channels.append(val2)
03266         self.object.parts.append(val1)
03267       start = end
03268       end += 4
03269       (length,) = _struct_I.unpack(str[start:end])
03270       self.object.params = []
03271       for i in range(0, length):
03272         val1 = articulation_msgs.msg.ParamMsg()
03273         start = end
03274         end += 4
03275         (length,) = _struct_I.unpack(str[start:end])
03276         start = end
03277         end += length
03278         if python3:
03279           val1.name = str[start:end].decode('utf-8')
03280         else:
03281           val1.name = str[start:end]
03282         _x = val1
03283         start = end
03284         end += 9
03285         (_x.value, _x.type,) = _struct_dB.unpack(str[start:end])
03286         self.object.params.append(val1)
03287       start = end
03288       end += 4
03289       (length,) = _struct_I.unpack(str[start:end])
03290       self.object.models = []
03291       for i in range(0, length):
03292         val1 = articulation_msgs.msg.ModelMsg()
03293         _v213 = val1.header
03294         start = end
03295         end += 4
03296         (_v213.seq,) = _struct_I.unpack(str[start:end])
03297         _v214 = _v213.stamp
03298         _x = _v214
03299         start = end
03300         end += 8
03301         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03302         start = end
03303         end += 4
03304         (length,) = _struct_I.unpack(str[start:end])
03305         start = end
03306         end += length
03307         if python3:
03308           _v213.frame_id = str[start:end].decode('utf-8')
03309         else:
03310           _v213.frame_id = str[start:end]
03311         start = end
03312         end += 4
03313         (val1.id,) = _struct_i.unpack(str[start:end])
03314         start = end
03315         end += 4
03316         (length,) = _struct_I.unpack(str[start:end])
03317         start = end
03318         end += length
03319         if python3:
03320           val1.name = str[start:end].decode('utf-8')
03321         else:
03322           val1.name = str[start:end]
03323         start = end
03324         end += 4
03325         (length,) = _struct_I.unpack(str[start:end])
03326         val1.params = []
03327         for i in range(0, length):
03328           val2 = articulation_msgs.msg.ParamMsg()
03329           start = end
03330           end += 4
03331           (length,) = _struct_I.unpack(str[start:end])
03332           start = end
03333           end += length
03334           if python3:
03335             val2.name = str[start:end].decode('utf-8')
03336           else:
03337             val2.name = str[start:end]
03338           _x = val2
03339           start = end
03340           end += 9
03341           (_x.value, _x.type,) = _struct_dB.unpack(str[start:end])
03342           val1.params.append(val2)
03343         _v215 = val1.track
03344         _v216 = _v215.header
03345         start = end
03346         end += 4
03347         (_v216.seq,) = _struct_I.unpack(str[start:end])
03348         _v217 = _v216.stamp
03349         _x = _v217
03350         start = end
03351         end += 8
03352         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03353         start = end
03354         end += 4
03355         (length,) = _struct_I.unpack(str[start:end])
03356         start = end
03357         end += length
03358         if python3:
03359           _v216.frame_id = str[start:end].decode('utf-8')
03360         else:
03361           _v216.frame_id = str[start:end]
03362         start = end
03363         end += 4
03364         (_v215.id,) = _struct_i.unpack(str[start:end])
03365         start = end
03366         end += 4
03367         (length,) = _struct_I.unpack(str[start:end])
03368         _v215.pose = []
03369         for i in range(0, length):
03370           val3 = geometry_msgs.msg.Pose()
03371           _v218 = val3.position
03372           _x = _v218
03373           start = end
03374           end += 24
03375           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03376           _v219 = val3.orientation
03377           _x = _v219
03378           start = end
03379           end += 32
03380           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03381           _v215.pose.append(val3)
03382         start = end
03383         end += 4
03384         (length,) = _struct_I.unpack(str[start:end])
03385         _v215.pose_headers = []
03386         for i in range(0, length):
03387           val3 = std_msgs.msg.Header()
03388           start = end
03389           end += 4
03390           (val3.seq,) = _struct_I.unpack(str[start:end])
03391           _v220 = val3.stamp
03392           _x = _v220
03393           start = end
03394           end += 8
03395           (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03396           start = end
03397           end += 4
03398           (length,) = _struct_I.unpack(str[start:end])
03399           start = end
03400           end += length
03401           if python3:
03402             val3.frame_id = str[start:end].decode('utf-8')
03403           else:
03404             val3.frame_id = str[start:end]
03405           _v215.pose_headers.append(val3)
03406         start = end
03407         end += 4
03408         (length,) = _struct_I.unpack(str[start:end])
03409         _v215.pose_projected = []
03410         for i in range(0, length):
03411           val3 = geometry_msgs.msg.Pose()
03412           _v221 = val3.position
03413           _x = _v221
03414           start = end
03415           end += 24
03416           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03417           _v222 = val3.orientation
03418           _x = _v222
03419           start = end
03420           end += 32
03421           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03422           _v215.pose_projected.append(val3)
03423         start = end
03424         end += 4
03425         (length,) = _struct_I.unpack(str[start:end])
03426         _v215.pose_resampled = []
03427         for i in range(0, length):
03428           val3 = geometry_msgs.msg.Pose()
03429           _v223 = val3.position
03430           _x = _v223
03431           start = end
03432           end += 24
03433           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03434           _v224 = val3.orientation
03435           _x = _v224
03436           start = end
03437           end += 32
03438           (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03439           _v215.pose_resampled.append(val3)
03440         start = end
03441         end += 4
03442         (length,) = _struct_I.unpack(str[start:end])
03443         pattern = '<%sI'%length
03444         start = end
03445         end += struct.calcsize(pattern)
03446         _v215.pose_flags = numpy.frombuffer(str[start:end], dtype=numpy.uint32, count=length)
03447         start = end
03448         end += 4
03449         (length,) = _struct_I.unpack(str[start:end])
03450         _v215.channels = []
03451         for i in range(0, length):
03452           val3 = sensor_msgs.msg.ChannelFloat32()
03453           start = end
03454           end += 4
03455           (length,) = _struct_I.unpack(str[start:end])
03456           start = end
03457           end += length
03458           if python3:
03459             val3.name = str[start:end].decode('utf-8')
03460           else:
03461             val3.name = str[start:end]
03462           start = end
03463           end += 4
03464           (length,) = _struct_I.unpack(str[start:end])
03465           pattern = '<%sf'%length
03466           start = end
03467           end += struct.calcsize(pattern)
03468           val3.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
03469           _v215.channels.append(val3)
03470         self.object.models.append(val1)
03471       start = end
03472       end += 4
03473       (length,) = _struct_I.unpack(str[start:end])
03474       self.object.markers.markers = []
03475       for i in range(0, length):
03476         val1 = visualization_msgs.msg.Marker()
03477         _v225 = val1.header
03478         start = end
03479         end += 4
03480         (_v225.seq,) = _struct_I.unpack(str[start:end])
03481         _v226 = _v225.stamp
03482         _x = _v226
03483         start = end
03484         end += 8
03485         (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
03486         start = end
03487         end += 4
03488         (length,) = _struct_I.unpack(str[start:end])
03489         start = end
03490         end += length
03491         if python3:
03492           _v225.frame_id = str[start:end].decode('utf-8')
03493         else:
03494           _v225.frame_id = str[start:end]
03495         start = end
03496         end += 4
03497         (length,) = _struct_I.unpack(str[start:end])
03498         start = end
03499         end += length
03500         if python3:
03501           val1.ns = str[start:end].decode('utf-8')
03502         else:
03503           val1.ns = str[start:end]
03504         _x = val1
03505         start = end
03506         end += 12
03507         (_x.id, _x.type, _x.action,) = _struct_3i.unpack(str[start:end])
03508         _v227 = val1.pose
03509         _v228 = _v227.position
03510         _x = _v228
03511         start = end
03512         end += 24
03513         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03514         _v229 = _v227.orientation
03515         _x = _v229
03516         start = end
03517         end += 32
03518         (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
03519         _v230 = val1.scale
03520         _x = _v230
03521         start = end
03522         end += 24
03523         (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03524         _v231 = val1.color
03525         _x = _v231
03526         start = end
03527         end += 16
03528         (_x.r, _x.g, _x.b, _x.a,) = _struct_4f.unpack(str[start:end])
03529         _v232 = val1.lifetime
03530         _x = _v232
03531         start = end
03532         end += 8
03533         (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
03534         start = end
03535         end += 1
03536         (val1.frame_locked,) = _struct_B.unpack(str[start:end])
03537         val1.frame_locked = bool(val1.frame_locked)
03538         start = end
03539         end += 4
03540         (length,) = _struct_I.unpack(str[start:end])
03541         val1.points = []
03542         for i in range(0, length):
03543           val2 = geometry_msgs.msg.Point()
03544           _x = val2
03545           start = end
03546           end += 24
03547           (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
03548           val1.points.append(val2)
03549         start = end
03550         end += 4
03551         (length,) = _struct_I.unpack(str[start:end])
03552         val1.colors = []
03553         for i in range(0, length):
03554           val2 = std_msgs.msg.ColorRGBA()
03555           _x = val2
03556           start = end
03557           end += 16
03558           (_x.r, _x.g, _x.b, _x.a,) = _struct_4f.unpack(str[start:end])
03559           val1.colors.append(val2)
03560         start = end
03561         end += 4
03562         (length,) = _struct_I.unpack(str[start:end])
03563         start = end
03564         end += length
03565         if python3:
03566           val1.text = str[start:end].decode('utf-8')
03567         else:
03568           val1.text = str[start:end]
03569         start = end
03570         end += 4
03571         (length,) = _struct_I.unpack(str[start:end])
03572         start = end
03573         end += length
03574         if python3:
03575           val1.mesh_resource = str[start:end].decode('utf-8')
03576         else:
03577           val1.mesh_resource = str[start:end]
03578         start = end
03579         end += 1
03580         (val1.mesh_use_embedded_materials,) = _struct_B.unpack(str[start:end])
03581         val1.mesh_use_embedded_materials = bool(val1.mesh_use_embedded_materials)
03582         self.object.markers.markers.append(val1)
03583       return self
03584     except struct.error as e:
03585       raise genpy.DeserializationError(e) #most likely buffer underfill
03586 
03587 _struct_I = genpy.struct_I
03588 _struct_B = struct.Struct("<B")
03589 _struct_dB = struct.Struct("<dB")
03590 _struct_3i = struct.Struct("<3i")
03591 _struct_2i = struct.Struct("<2i")
03592 _struct_i = struct.Struct("<i")
03593 _struct_3I = struct.Struct("<3I")
03594 _struct_4f = struct.Struct("<4f")
03595 _struct_4d = struct.Struct("<4d")
03596 _struct_2I = struct.Struct("<2I")
03597 _struct_3d = struct.Struct("<3d")
03598 class ArticulatedObjectSrv(object):
03599   _type          = 'articulation_msgs/ArticulatedObjectSrv'
03600   _md5sum = '15c3db27c762fecdf8ce2ef6fbe54b87'
03601   _request_class  = ArticulatedObjectSrvRequest
03602   _response_class = ArticulatedObjectSrvResponse
 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