00001 """autogenerated by genpy from calibration_msgs/JointStateCalibrationPattern.msg. Do not edit."""
00002 import sys
00003 python3 = True if sys.hexversion > 0x03000000 else False
00004 import genpy
00005 import struct
00006
00007 import sensor_msgs.msg
00008 import geometry_msgs.msg
00009 import std_msgs.msg
00010
00011 class JointStateCalibrationPattern(genpy.Message):
00012 _md5sum = "c80e9cf8e7942eba44a6d32e3c75bf59"
00013 _type = "calibration_msgs/JointStateCalibrationPattern"
00014 _has_header = True
00015 _full_text = """Header header
00016 geometry_msgs/Point[] object_points
00017 sensor_msgs/JointState[] joint_points
00018
00019
00020 ================================================================================
00021 MSG: std_msgs/Header
00022 # Standard metadata for higher-level stamped data types.
00023 # This is generally used to communicate timestamped data
00024 # in a particular coordinate frame.
00025 #
00026 # sequence ID: consecutively increasing ID
00027 uint32 seq
00028 #Two-integer timestamp that is expressed as:
00029 # * stamp.secs: seconds (stamp_secs) since epoch
00030 # * stamp.nsecs: nanoseconds since stamp_secs
00031 # time-handling sugar is provided by the client library
00032 time stamp
00033 #Frame this data is associated with
00034 # 0: no frame
00035 # 1: global frame
00036 string frame_id
00037
00038 ================================================================================
00039 MSG: geometry_msgs/Point
00040 # This contains the position of a point in free space
00041 float64 x
00042 float64 y
00043 float64 z
00044
00045 ================================================================================
00046 MSG: sensor_msgs/JointState
00047 # This is a message that holds data to describe the state of a set of torque controlled joints.
00048 #
00049 # The state of each joint (revolute or prismatic) is defined by:
00050 # * the position of the joint (rad or m),
00051 # * the velocity of the joint (rad/s or m/s) and
00052 # * the effort that is applied in the joint (Nm or N).
00053 #
00054 # Each joint is uniquely identified by its name
00055 # The header specifies the time at which the joint states were recorded. All the joint states
00056 # in one message have to be recorded at the same time.
00057 #
00058 # This message consists of a multiple arrays, one for each part of the joint state.
00059 # The goal is to make each of the fields optional. When e.g. your joints have no
00060 # effort associated with them, you can leave the effort array empty.
00061 #
00062 # All arrays in this message should have the same size, or be empty.
00063 # This is the only way to uniquely associate the joint name with the correct
00064 # states.
00065
00066
00067 Header header
00068
00069 string[] name
00070 float64[] position
00071 float64[] velocity
00072 float64[] effort
00073
00074 """
00075 __slots__ = ['header','object_points','joint_points']
00076 _slot_types = ['std_msgs/Header','geometry_msgs/Point[]','sensor_msgs/JointState[]']
00077
00078 def __init__(self, *args, **kwds):
00079 """
00080 Constructor. Any message fields that are implicitly/explicitly
00081 set to None will be assigned a default value. The recommend
00082 use is keyword arguments as this is more robust to future message
00083 changes. You cannot mix in-order arguments and keyword arguments.
00084
00085 The available fields are:
00086 header,object_points,joint_points
00087
00088 :param args: complete set of field values, in .msg order
00089 :param kwds: use keyword arguments corresponding to message field names
00090 to set specific fields.
00091 """
00092 if args or kwds:
00093 super(JointStateCalibrationPattern, self).__init__(*args, **kwds)
00094
00095 if self.header is None:
00096 self.header = std_msgs.msg.Header()
00097 if self.object_points is None:
00098 self.object_points = []
00099 if self.joint_points is None:
00100 self.joint_points = []
00101 else:
00102 self.header = std_msgs.msg.Header()
00103 self.object_points = []
00104 self.joint_points = []
00105
00106 def _get_types(self):
00107 """
00108 internal API method
00109 """
00110 return self._slot_types
00111
00112 def serialize(self, buff):
00113 """
00114 serialize message into buffer
00115 :param buff: buffer, ``StringIO``
00116 """
00117 try:
00118 _x = self
00119 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00120 _x = self.header.frame_id
00121 length = len(_x)
00122 if python3 or type(_x) == unicode:
00123 _x = _x.encode('utf-8')
00124 length = len(_x)
00125 buff.write(struct.pack('<I%ss'%length, length, _x))
00126 length = len(self.object_points)
00127 buff.write(_struct_I.pack(length))
00128 for val1 in self.object_points:
00129 _x = val1
00130 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00131 length = len(self.joint_points)
00132 buff.write(_struct_I.pack(length))
00133 for val1 in self.joint_points:
00134 _v1 = val1.header
00135 buff.write(_struct_I.pack(_v1.seq))
00136 _v2 = _v1.stamp
00137 _x = _v2
00138 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00139 _x = _v1.frame_id
00140 length = len(_x)
00141 if python3 or type(_x) == unicode:
00142 _x = _x.encode('utf-8')
00143 length = len(_x)
00144 buff.write(struct.pack('<I%ss'%length, length, _x))
00145 length = len(val1.name)
00146 buff.write(_struct_I.pack(length))
00147 for val2 in val1.name:
00148 length = len(val2)
00149 if python3 or type(val2) == unicode:
00150 val2 = val2.encode('utf-8')
00151 length = len(val2)
00152 buff.write(struct.pack('<I%ss'%length, length, val2))
00153 length = len(val1.position)
00154 buff.write(_struct_I.pack(length))
00155 pattern = '<%sd'%length
00156 buff.write(struct.pack(pattern, *val1.position))
00157 length = len(val1.velocity)
00158 buff.write(_struct_I.pack(length))
00159 pattern = '<%sd'%length
00160 buff.write(struct.pack(pattern, *val1.velocity))
00161 length = len(val1.effort)
00162 buff.write(_struct_I.pack(length))
00163 pattern = '<%sd'%length
00164 buff.write(struct.pack(pattern, *val1.effort))
00165 except struct.error as se: self._check_types(se)
00166 except TypeError as te: self._check_types(te)
00167
00168 def deserialize(self, str):
00169 """
00170 unpack serialized message in str into this message instance
00171 :param str: byte array of serialized message, ``str``
00172 """
00173 try:
00174 if self.header is None:
00175 self.header = std_msgs.msg.Header()
00176 if self.object_points is None:
00177 self.object_points = None
00178 if self.joint_points is None:
00179 self.joint_points = None
00180 end = 0
00181 _x = self
00182 start = end
00183 end += 12
00184 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00185 start = end
00186 end += 4
00187 (length,) = _struct_I.unpack(str[start:end])
00188 start = end
00189 end += length
00190 if python3:
00191 self.header.frame_id = str[start:end].decode('utf-8')
00192 else:
00193 self.header.frame_id = str[start:end]
00194 start = end
00195 end += 4
00196 (length,) = _struct_I.unpack(str[start:end])
00197 self.object_points = []
00198 for i in range(0, length):
00199 val1 = geometry_msgs.msg.Point()
00200 _x = val1
00201 start = end
00202 end += 24
00203 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00204 self.object_points.append(val1)
00205 start = end
00206 end += 4
00207 (length,) = _struct_I.unpack(str[start:end])
00208 self.joint_points = []
00209 for i in range(0, length):
00210 val1 = sensor_msgs.msg.JointState()
00211 _v3 = val1.header
00212 start = end
00213 end += 4
00214 (_v3.seq,) = _struct_I.unpack(str[start:end])
00215 _v4 = _v3.stamp
00216 _x = _v4
00217 start = end
00218 end += 8
00219 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00220 start = end
00221 end += 4
00222 (length,) = _struct_I.unpack(str[start:end])
00223 start = end
00224 end += length
00225 if python3:
00226 _v3.frame_id = str[start:end].decode('utf-8')
00227 else:
00228 _v3.frame_id = str[start:end]
00229 start = end
00230 end += 4
00231 (length,) = _struct_I.unpack(str[start:end])
00232 val1.name = []
00233 for i in range(0, length):
00234 start = end
00235 end += 4
00236 (length,) = _struct_I.unpack(str[start:end])
00237 start = end
00238 end += length
00239 if python3:
00240 val2 = str[start:end].decode('utf-8')
00241 else:
00242 val2 = str[start:end]
00243 val1.name.append(val2)
00244 start = end
00245 end += 4
00246 (length,) = _struct_I.unpack(str[start:end])
00247 pattern = '<%sd'%length
00248 start = end
00249 end += struct.calcsize(pattern)
00250 val1.position = struct.unpack(pattern, str[start:end])
00251 start = end
00252 end += 4
00253 (length,) = _struct_I.unpack(str[start:end])
00254 pattern = '<%sd'%length
00255 start = end
00256 end += struct.calcsize(pattern)
00257 val1.velocity = struct.unpack(pattern, str[start:end])
00258 start = end
00259 end += 4
00260 (length,) = _struct_I.unpack(str[start:end])
00261 pattern = '<%sd'%length
00262 start = end
00263 end += struct.calcsize(pattern)
00264 val1.effort = struct.unpack(pattern, str[start:end])
00265 self.joint_points.append(val1)
00266 return self
00267 except struct.error as e:
00268 raise genpy.DeserializationError(e)
00269
00270
00271 def serialize_numpy(self, buff, numpy):
00272 """
00273 serialize message with numpy array types into buffer
00274 :param buff: buffer, ``StringIO``
00275 :param numpy: numpy python module
00276 """
00277 try:
00278 _x = self
00279 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00280 _x = self.header.frame_id
00281 length = len(_x)
00282 if python3 or type(_x) == unicode:
00283 _x = _x.encode('utf-8')
00284 length = len(_x)
00285 buff.write(struct.pack('<I%ss'%length, length, _x))
00286 length = len(self.object_points)
00287 buff.write(_struct_I.pack(length))
00288 for val1 in self.object_points:
00289 _x = val1
00290 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00291 length = len(self.joint_points)
00292 buff.write(_struct_I.pack(length))
00293 for val1 in self.joint_points:
00294 _v5 = val1.header
00295 buff.write(_struct_I.pack(_v5.seq))
00296 _v6 = _v5.stamp
00297 _x = _v6
00298 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00299 _x = _v5.frame_id
00300 length = len(_x)
00301 if python3 or type(_x) == unicode:
00302 _x = _x.encode('utf-8')
00303 length = len(_x)
00304 buff.write(struct.pack('<I%ss'%length, length, _x))
00305 length = len(val1.name)
00306 buff.write(_struct_I.pack(length))
00307 for val2 in val1.name:
00308 length = len(val2)
00309 if python3 or type(val2) == unicode:
00310 val2 = val2.encode('utf-8')
00311 length = len(val2)
00312 buff.write(struct.pack('<I%ss'%length, length, val2))
00313 length = len(val1.position)
00314 buff.write(_struct_I.pack(length))
00315 pattern = '<%sd'%length
00316 buff.write(val1.position.tostring())
00317 length = len(val1.velocity)
00318 buff.write(_struct_I.pack(length))
00319 pattern = '<%sd'%length
00320 buff.write(val1.velocity.tostring())
00321 length = len(val1.effort)
00322 buff.write(_struct_I.pack(length))
00323 pattern = '<%sd'%length
00324 buff.write(val1.effort.tostring())
00325 except struct.error as se: self._check_types(se)
00326 except TypeError as te: self._check_types(te)
00327
00328 def deserialize_numpy(self, str, numpy):
00329 """
00330 unpack serialized message in str into this message instance using numpy for array types
00331 :param str: byte array of serialized message, ``str``
00332 :param numpy: numpy python module
00333 """
00334 try:
00335 if self.header is None:
00336 self.header = std_msgs.msg.Header()
00337 if self.object_points is None:
00338 self.object_points = None
00339 if self.joint_points is None:
00340 self.joint_points = None
00341 end = 0
00342 _x = self
00343 start = end
00344 end += 12
00345 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00346 start = end
00347 end += 4
00348 (length,) = _struct_I.unpack(str[start:end])
00349 start = end
00350 end += length
00351 if python3:
00352 self.header.frame_id = str[start:end].decode('utf-8')
00353 else:
00354 self.header.frame_id = str[start:end]
00355 start = end
00356 end += 4
00357 (length,) = _struct_I.unpack(str[start:end])
00358 self.object_points = []
00359 for i in range(0, length):
00360 val1 = geometry_msgs.msg.Point()
00361 _x = val1
00362 start = end
00363 end += 24
00364 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00365 self.object_points.append(val1)
00366 start = end
00367 end += 4
00368 (length,) = _struct_I.unpack(str[start:end])
00369 self.joint_points = []
00370 for i in range(0, length):
00371 val1 = sensor_msgs.msg.JointState()
00372 _v7 = val1.header
00373 start = end
00374 end += 4
00375 (_v7.seq,) = _struct_I.unpack(str[start:end])
00376 _v8 = _v7.stamp
00377 _x = _v8
00378 start = end
00379 end += 8
00380 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00381 start = end
00382 end += 4
00383 (length,) = _struct_I.unpack(str[start:end])
00384 start = end
00385 end += length
00386 if python3:
00387 _v7.frame_id = str[start:end].decode('utf-8')
00388 else:
00389 _v7.frame_id = str[start:end]
00390 start = end
00391 end += 4
00392 (length,) = _struct_I.unpack(str[start:end])
00393 val1.name = []
00394 for i in range(0, length):
00395 start = end
00396 end += 4
00397 (length,) = _struct_I.unpack(str[start:end])
00398 start = end
00399 end += length
00400 if python3:
00401 val2 = str[start:end].decode('utf-8')
00402 else:
00403 val2 = str[start:end]
00404 val1.name.append(val2)
00405 start = end
00406 end += 4
00407 (length,) = _struct_I.unpack(str[start:end])
00408 pattern = '<%sd'%length
00409 start = end
00410 end += struct.calcsize(pattern)
00411 val1.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00412 start = end
00413 end += 4
00414 (length,) = _struct_I.unpack(str[start:end])
00415 pattern = '<%sd'%length
00416 start = end
00417 end += struct.calcsize(pattern)
00418 val1.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00419 start = end
00420 end += 4
00421 (length,) = _struct_I.unpack(str[start:end])
00422 pattern = '<%sd'%length
00423 start = end
00424 end += struct.calcsize(pattern)
00425 val1.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00426 self.joint_points.append(val1)
00427 return self
00428 except struct.error as e:
00429 raise genpy.DeserializationError(e)
00430
00431 _struct_I = genpy.struct_I
00432 _struct_3I = struct.Struct("<3I")
00433 _struct_2I = struct.Struct("<2I")
00434 _struct_3d = struct.Struct("<3d")