00001 """autogenerated by genmsg_py from FollowJointTrajectoryActionFeedback.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import trajectory_msgs.msg
00006 import control_msgs.msg
00007 import roslib.rostime
00008 import actionlib_msgs.msg
00009 import std_msgs.msg
00010
00011 class FollowJointTrajectoryActionFeedback(roslib.message.Message):
00012 _md5sum = "868e86353778bcb1c5689adaa01a40d7"
00013 _type = "control_msgs/FollowJointTrajectoryActionFeedback"
00014 _has_header = True
00015 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00016
00017 Header header
00018 actionlib_msgs/GoalStatus status
00019 FollowJointTrajectoryFeedback feedback
00020
00021 ================================================================================
00022 MSG: std_msgs/Header
00023 # Standard metadata for higher-level stamped data types.
00024 # This is generally used to communicate timestamped data
00025 # in a particular coordinate frame.
00026 #
00027 # sequence ID: consecutively increasing ID
00028 uint32 seq
00029 #Two-integer timestamp that is expressed as:
00030 # * stamp.secs: seconds (stamp_secs) since epoch
00031 # * stamp.nsecs: nanoseconds since stamp_secs
00032 # time-handling sugar is provided by the client library
00033 time stamp
00034 #Frame this data is associated with
00035 # 0: no frame
00036 # 1: global frame
00037 string frame_id
00038
00039 ================================================================================
00040 MSG: actionlib_msgs/GoalStatus
00041 GoalID goal_id
00042 uint8 status
00043 uint8 PENDING = 0 # The goal has yet to be processed by the action server
00044 uint8 ACTIVE = 1 # The goal is currently being processed by the action server
00045 uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing
00046 # and has since completed its execution (Terminal State)
00047 uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State)
00048 uint8 ABORTED = 4 # The goal was aborted during execution by the action server due
00049 # to some failure (Terminal State)
00050 uint8 REJECTED = 5 # The goal was rejected by the action server without being processed,
00051 # because the goal was unattainable or invalid (Terminal State)
00052 uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing
00053 # and has not yet completed execution
00054 uint8 RECALLING = 7 # The goal received a cancel request before it started executing,
00055 # but the action server has not yet confirmed that the goal is canceled
00056 uint8 RECALLED = 8 # The goal received a cancel request before it started executing
00057 # and was successfully cancelled (Terminal State)
00058 uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be
00059 # sent over the wire by an action server
00060
00061 #Allow for the user to associate a string with GoalStatus for debugging
00062 string text
00063
00064
00065 ================================================================================
00066 MSG: actionlib_msgs/GoalID
00067 # The stamp should store the time at which this goal was requested.
00068 # It is used by an action server when it tries to preempt all
00069 # goals that were requested before a certain time
00070 time stamp
00071
00072 # The id provides a way to associate feedback and
00073 # result message with specific goal requests. The id
00074 # specified must be unique.
00075 string id
00076
00077
00078 ================================================================================
00079 MSG: control_msgs/FollowJointTrajectoryFeedback
00080 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00081 Header header
00082 string[] joint_names
00083 trajectory_msgs/JointTrajectoryPoint desired
00084 trajectory_msgs/JointTrajectoryPoint actual
00085 trajectory_msgs/JointTrajectoryPoint error
00086
00087
00088 ================================================================================
00089 MSG: trajectory_msgs/JointTrajectoryPoint
00090 float64[] positions
00091 float64[] velocities
00092 float64[] accelerations
00093 duration time_from_start
00094 """
00095 __slots__ = ['header','status','feedback']
00096 _slot_types = ['Header','actionlib_msgs/GoalStatus','control_msgs/FollowJointTrajectoryFeedback']
00097
00098 def __init__(self, *args, **kwds):
00099 """
00100 Constructor. Any message fields that are implicitly/explicitly
00101 set to None will be assigned a default value. The recommend
00102 use is keyword arguments as this is more robust to future message
00103 changes. You cannot mix in-order arguments and keyword arguments.
00104
00105 The available fields are:
00106 header,status,feedback
00107
00108 @param args: complete set of field values, in .msg order
00109 @param kwds: use keyword arguments corresponding to message field names
00110 to set specific fields.
00111 """
00112 if args or kwds:
00113 super(FollowJointTrajectoryActionFeedback, self).__init__(*args, **kwds)
00114
00115 if self.header is None:
00116 self.header = std_msgs.msg._Header.Header()
00117 if self.status is None:
00118 self.status = actionlib_msgs.msg.GoalStatus()
00119 if self.feedback is None:
00120 self.feedback = control_msgs.msg.FollowJointTrajectoryFeedback()
00121 else:
00122 self.header = std_msgs.msg._Header.Header()
00123 self.status = actionlib_msgs.msg.GoalStatus()
00124 self.feedback = control_msgs.msg.FollowJointTrajectoryFeedback()
00125
00126 def _get_types(self):
00127 """
00128 internal API method
00129 """
00130 return self._slot_types
00131
00132 def serialize(self, buff):
00133 """
00134 serialize message into buffer
00135 @param buff: buffer
00136 @type buff: StringIO
00137 """
00138 try:
00139 _x = self
00140 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00141 _x = self.header.frame_id
00142 length = len(_x)
00143 buff.write(struct.pack('<I%ss'%length, length, _x))
00144 _x = self
00145 buff.write(_struct_2I.pack(_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs))
00146 _x = self.status.goal_id.id
00147 length = len(_x)
00148 buff.write(struct.pack('<I%ss'%length, length, _x))
00149 buff.write(_struct_B.pack(self.status.status))
00150 _x = self.status.text
00151 length = len(_x)
00152 buff.write(struct.pack('<I%ss'%length, length, _x))
00153 _x = self
00154 buff.write(_struct_3I.pack(_x.feedback.header.seq, _x.feedback.header.stamp.secs, _x.feedback.header.stamp.nsecs))
00155 _x = self.feedback.header.frame_id
00156 length = len(_x)
00157 buff.write(struct.pack('<I%ss'%length, length, _x))
00158 length = len(self.feedback.joint_names)
00159 buff.write(_struct_I.pack(length))
00160 for val1 in self.feedback.joint_names:
00161 length = len(val1)
00162 buff.write(struct.pack('<I%ss'%length, length, val1))
00163 length = len(self.feedback.desired.positions)
00164 buff.write(_struct_I.pack(length))
00165 pattern = '<%sd'%length
00166 buff.write(struct.pack(pattern, *self.feedback.desired.positions))
00167 length = len(self.feedback.desired.velocities)
00168 buff.write(_struct_I.pack(length))
00169 pattern = '<%sd'%length
00170 buff.write(struct.pack(pattern, *self.feedback.desired.velocities))
00171 length = len(self.feedback.desired.accelerations)
00172 buff.write(_struct_I.pack(length))
00173 pattern = '<%sd'%length
00174 buff.write(struct.pack(pattern, *self.feedback.desired.accelerations))
00175 _x = self
00176 buff.write(_struct_2i.pack(_x.feedback.desired.time_from_start.secs, _x.feedback.desired.time_from_start.nsecs))
00177 length = len(self.feedback.actual.positions)
00178 buff.write(_struct_I.pack(length))
00179 pattern = '<%sd'%length
00180 buff.write(struct.pack(pattern, *self.feedback.actual.positions))
00181 length = len(self.feedback.actual.velocities)
00182 buff.write(_struct_I.pack(length))
00183 pattern = '<%sd'%length
00184 buff.write(struct.pack(pattern, *self.feedback.actual.velocities))
00185 length = len(self.feedback.actual.accelerations)
00186 buff.write(_struct_I.pack(length))
00187 pattern = '<%sd'%length
00188 buff.write(struct.pack(pattern, *self.feedback.actual.accelerations))
00189 _x = self
00190 buff.write(_struct_2i.pack(_x.feedback.actual.time_from_start.secs, _x.feedback.actual.time_from_start.nsecs))
00191 length = len(self.feedback.error.positions)
00192 buff.write(_struct_I.pack(length))
00193 pattern = '<%sd'%length
00194 buff.write(struct.pack(pattern, *self.feedback.error.positions))
00195 length = len(self.feedback.error.velocities)
00196 buff.write(_struct_I.pack(length))
00197 pattern = '<%sd'%length
00198 buff.write(struct.pack(pattern, *self.feedback.error.velocities))
00199 length = len(self.feedback.error.accelerations)
00200 buff.write(_struct_I.pack(length))
00201 pattern = '<%sd'%length
00202 buff.write(struct.pack(pattern, *self.feedback.error.accelerations))
00203 _x = self
00204 buff.write(_struct_2i.pack(_x.feedback.error.time_from_start.secs, _x.feedback.error.time_from_start.nsecs))
00205 except struct.error, se: self._check_types(se)
00206 except TypeError, te: self._check_types(te)
00207
00208 def deserialize(self, str):
00209 """
00210 unpack serialized message in str into this message instance
00211 @param str: byte array of serialized message
00212 @type str: str
00213 """
00214 try:
00215 if self.header is None:
00216 self.header = std_msgs.msg._Header.Header()
00217 if self.status is None:
00218 self.status = actionlib_msgs.msg.GoalStatus()
00219 if self.feedback is None:
00220 self.feedback = control_msgs.msg.FollowJointTrajectoryFeedback()
00221 end = 0
00222 _x = self
00223 start = end
00224 end += 12
00225 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00226 start = end
00227 end += 4
00228 (length,) = _struct_I.unpack(str[start:end])
00229 start = end
00230 end += length
00231 self.header.frame_id = str[start:end]
00232 _x = self
00233 start = end
00234 end += 8
00235 (_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00236 start = end
00237 end += 4
00238 (length,) = _struct_I.unpack(str[start:end])
00239 start = end
00240 end += length
00241 self.status.goal_id.id = str[start:end]
00242 start = end
00243 end += 1
00244 (self.status.status,) = _struct_B.unpack(str[start:end])
00245 start = end
00246 end += 4
00247 (length,) = _struct_I.unpack(str[start:end])
00248 start = end
00249 end += length
00250 self.status.text = str[start:end]
00251 _x = self
00252 start = end
00253 end += 12
00254 (_x.feedback.header.seq, _x.feedback.header.stamp.secs, _x.feedback.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00255 start = end
00256 end += 4
00257 (length,) = _struct_I.unpack(str[start:end])
00258 start = end
00259 end += length
00260 self.feedback.header.frame_id = str[start:end]
00261 start = end
00262 end += 4
00263 (length,) = _struct_I.unpack(str[start:end])
00264 self.feedback.joint_names = []
00265 for i in xrange(0, length):
00266 start = end
00267 end += 4
00268 (length,) = _struct_I.unpack(str[start:end])
00269 start = end
00270 end += length
00271 val1 = str[start:end]
00272 self.feedback.joint_names.append(val1)
00273 start = end
00274 end += 4
00275 (length,) = _struct_I.unpack(str[start:end])
00276 pattern = '<%sd'%length
00277 start = end
00278 end += struct.calcsize(pattern)
00279 self.feedback.desired.positions = struct.unpack(pattern, str[start:end])
00280 start = end
00281 end += 4
00282 (length,) = _struct_I.unpack(str[start:end])
00283 pattern = '<%sd'%length
00284 start = end
00285 end += struct.calcsize(pattern)
00286 self.feedback.desired.velocities = struct.unpack(pattern, str[start:end])
00287 start = end
00288 end += 4
00289 (length,) = _struct_I.unpack(str[start:end])
00290 pattern = '<%sd'%length
00291 start = end
00292 end += struct.calcsize(pattern)
00293 self.feedback.desired.accelerations = struct.unpack(pattern, str[start:end])
00294 _x = self
00295 start = end
00296 end += 8
00297 (_x.feedback.desired.time_from_start.secs, _x.feedback.desired.time_from_start.nsecs,) = _struct_2i.unpack(str[start:end])
00298 start = end
00299 end += 4
00300 (length,) = _struct_I.unpack(str[start:end])
00301 pattern = '<%sd'%length
00302 start = end
00303 end += struct.calcsize(pattern)
00304 self.feedback.actual.positions = struct.unpack(pattern, str[start:end])
00305 start = end
00306 end += 4
00307 (length,) = _struct_I.unpack(str[start:end])
00308 pattern = '<%sd'%length
00309 start = end
00310 end += struct.calcsize(pattern)
00311 self.feedback.actual.velocities = struct.unpack(pattern, str[start:end])
00312 start = end
00313 end += 4
00314 (length,) = _struct_I.unpack(str[start:end])
00315 pattern = '<%sd'%length
00316 start = end
00317 end += struct.calcsize(pattern)
00318 self.feedback.actual.accelerations = struct.unpack(pattern, str[start:end])
00319 _x = self
00320 start = end
00321 end += 8
00322 (_x.feedback.actual.time_from_start.secs, _x.feedback.actual.time_from_start.nsecs,) = _struct_2i.unpack(str[start:end])
00323 start = end
00324 end += 4
00325 (length,) = _struct_I.unpack(str[start:end])
00326 pattern = '<%sd'%length
00327 start = end
00328 end += struct.calcsize(pattern)
00329 self.feedback.error.positions = struct.unpack(pattern, str[start:end])
00330 start = end
00331 end += 4
00332 (length,) = _struct_I.unpack(str[start:end])
00333 pattern = '<%sd'%length
00334 start = end
00335 end += struct.calcsize(pattern)
00336 self.feedback.error.velocities = struct.unpack(pattern, str[start:end])
00337 start = end
00338 end += 4
00339 (length,) = _struct_I.unpack(str[start:end])
00340 pattern = '<%sd'%length
00341 start = end
00342 end += struct.calcsize(pattern)
00343 self.feedback.error.accelerations = struct.unpack(pattern, str[start:end])
00344 _x = self
00345 start = end
00346 end += 8
00347 (_x.feedback.error.time_from_start.secs, _x.feedback.error.time_from_start.nsecs,) = _struct_2i.unpack(str[start:end])
00348 return self
00349 except struct.error, e:
00350 raise roslib.message.DeserializationError(e)
00351
00352
00353 def serialize_numpy(self, buff, numpy):
00354 """
00355 serialize message with numpy array types into buffer
00356 @param buff: buffer
00357 @type buff: StringIO
00358 @param numpy: numpy python module
00359 @type numpy module
00360 """
00361 try:
00362 _x = self
00363 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00364 _x = self.header.frame_id
00365 length = len(_x)
00366 buff.write(struct.pack('<I%ss'%length, length, _x))
00367 _x = self
00368 buff.write(_struct_2I.pack(_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs))
00369 _x = self.status.goal_id.id
00370 length = len(_x)
00371 buff.write(struct.pack('<I%ss'%length, length, _x))
00372 buff.write(_struct_B.pack(self.status.status))
00373 _x = self.status.text
00374 length = len(_x)
00375 buff.write(struct.pack('<I%ss'%length, length, _x))
00376 _x = self
00377 buff.write(_struct_3I.pack(_x.feedback.header.seq, _x.feedback.header.stamp.secs, _x.feedback.header.stamp.nsecs))
00378 _x = self.feedback.header.frame_id
00379 length = len(_x)
00380 buff.write(struct.pack('<I%ss'%length, length, _x))
00381 length = len(self.feedback.joint_names)
00382 buff.write(_struct_I.pack(length))
00383 for val1 in self.feedback.joint_names:
00384 length = len(val1)
00385 buff.write(struct.pack('<I%ss'%length, length, val1))
00386 length = len(self.feedback.desired.positions)
00387 buff.write(_struct_I.pack(length))
00388 pattern = '<%sd'%length
00389 buff.write(self.feedback.desired.positions.tostring())
00390 length = len(self.feedback.desired.velocities)
00391 buff.write(_struct_I.pack(length))
00392 pattern = '<%sd'%length
00393 buff.write(self.feedback.desired.velocities.tostring())
00394 length = len(self.feedback.desired.accelerations)
00395 buff.write(_struct_I.pack(length))
00396 pattern = '<%sd'%length
00397 buff.write(self.feedback.desired.accelerations.tostring())
00398 _x = self
00399 buff.write(_struct_2i.pack(_x.feedback.desired.time_from_start.secs, _x.feedback.desired.time_from_start.nsecs))
00400 length = len(self.feedback.actual.positions)
00401 buff.write(_struct_I.pack(length))
00402 pattern = '<%sd'%length
00403 buff.write(self.feedback.actual.positions.tostring())
00404 length = len(self.feedback.actual.velocities)
00405 buff.write(_struct_I.pack(length))
00406 pattern = '<%sd'%length
00407 buff.write(self.feedback.actual.velocities.tostring())
00408 length = len(self.feedback.actual.accelerations)
00409 buff.write(_struct_I.pack(length))
00410 pattern = '<%sd'%length
00411 buff.write(self.feedback.actual.accelerations.tostring())
00412 _x = self
00413 buff.write(_struct_2i.pack(_x.feedback.actual.time_from_start.secs, _x.feedback.actual.time_from_start.nsecs))
00414 length = len(self.feedback.error.positions)
00415 buff.write(_struct_I.pack(length))
00416 pattern = '<%sd'%length
00417 buff.write(self.feedback.error.positions.tostring())
00418 length = len(self.feedback.error.velocities)
00419 buff.write(_struct_I.pack(length))
00420 pattern = '<%sd'%length
00421 buff.write(self.feedback.error.velocities.tostring())
00422 length = len(self.feedback.error.accelerations)
00423 buff.write(_struct_I.pack(length))
00424 pattern = '<%sd'%length
00425 buff.write(self.feedback.error.accelerations.tostring())
00426 _x = self
00427 buff.write(_struct_2i.pack(_x.feedback.error.time_from_start.secs, _x.feedback.error.time_from_start.nsecs))
00428 except struct.error, se: self._check_types(se)
00429 except TypeError, te: self._check_types(te)
00430
00431 def deserialize_numpy(self, str, numpy):
00432 """
00433 unpack serialized message in str into this message instance using numpy for array types
00434 @param str: byte array of serialized message
00435 @type str: str
00436 @param numpy: numpy python module
00437 @type numpy: module
00438 """
00439 try:
00440 if self.header is None:
00441 self.header = std_msgs.msg._Header.Header()
00442 if self.status is None:
00443 self.status = actionlib_msgs.msg.GoalStatus()
00444 if self.feedback is None:
00445 self.feedback = control_msgs.msg.FollowJointTrajectoryFeedback()
00446 end = 0
00447 _x = self
00448 start = end
00449 end += 12
00450 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00451 start = end
00452 end += 4
00453 (length,) = _struct_I.unpack(str[start:end])
00454 start = end
00455 end += length
00456 self.header.frame_id = str[start:end]
00457 _x = self
00458 start = end
00459 end += 8
00460 (_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00461 start = end
00462 end += 4
00463 (length,) = _struct_I.unpack(str[start:end])
00464 start = end
00465 end += length
00466 self.status.goal_id.id = str[start:end]
00467 start = end
00468 end += 1
00469 (self.status.status,) = _struct_B.unpack(str[start:end])
00470 start = end
00471 end += 4
00472 (length,) = _struct_I.unpack(str[start:end])
00473 start = end
00474 end += length
00475 self.status.text = str[start:end]
00476 _x = self
00477 start = end
00478 end += 12
00479 (_x.feedback.header.seq, _x.feedback.header.stamp.secs, _x.feedback.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00480 start = end
00481 end += 4
00482 (length,) = _struct_I.unpack(str[start:end])
00483 start = end
00484 end += length
00485 self.feedback.header.frame_id = str[start:end]
00486 start = end
00487 end += 4
00488 (length,) = _struct_I.unpack(str[start:end])
00489 self.feedback.joint_names = []
00490 for i in xrange(0, length):
00491 start = end
00492 end += 4
00493 (length,) = _struct_I.unpack(str[start:end])
00494 start = end
00495 end += length
00496 val1 = str[start:end]
00497 self.feedback.joint_names.append(val1)
00498 start = end
00499 end += 4
00500 (length,) = _struct_I.unpack(str[start:end])
00501 pattern = '<%sd'%length
00502 start = end
00503 end += struct.calcsize(pattern)
00504 self.feedback.desired.positions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00505 start = end
00506 end += 4
00507 (length,) = _struct_I.unpack(str[start:end])
00508 pattern = '<%sd'%length
00509 start = end
00510 end += struct.calcsize(pattern)
00511 self.feedback.desired.velocities = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00512 start = end
00513 end += 4
00514 (length,) = _struct_I.unpack(str[start:end])
00515 pattern = '<%sd'%length
00516 start = end
00517 end += struct.calcsize(pattern)
00518 self.feedback.desired.accelerations = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00519 _x = self
00520 start = end
00521 end += 8
00522 (_x.feedback.desired.time_from_start.secs, _x.feedback.desired.time_from_start.nsecs,) = _struct_2i.unpack(str[start:end])
00523 start = end
00524 end += 4
00525 (length,) = _struct_I.unpack(str[start:end])
00526 pattern = '<%sd'%length
00527 start = end
00528 end += struct.calcsize(pattern)
00529 self.feedback.actual.positions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00530 start = end
00531 end += 4
00532 (length,) = _struct_I.unpack(str[start:end])
00533 pattern = '<%sd'%length
00534 start = end
00535 end += struct.calcsize(pattern)
00536 self.feedback.actual.velocities = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00537 start = end
00538 end += 4
00539 (length,) = _struct_I.unpack(str[start:end])
00540 pattern = '<%sd'%length
00541 start = end
00542 end += struct.calcsize(pattern)
00543 self.feedback.actual.accelerations = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00544 _x = self
00545 start = end
00546 end += 8
00547 (_x.feedback.actual.time_from_start.secs, _x.feedback.actual.time_from_start.nsecs,) = _struct_2i.unpack(str[start:end])
00548 start = end
00549 end += 4
00550 (length,) = _struct_I.unpack(str[start:end])
00551 pattern = '<%sd'%length
00552 start = end
00553 end += struct.calcsize(pattern)
00554 self.feedback.error.positions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00555 start = end
00556 end += 4
00557 (length,) = _struct_I.unpack(str[start:end])
00558 pattern = '<%sd'%length
00559 start = end
00560 end += struct.calcsize(pattern)
00561 self.feedback.error.velocities = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00562 start = end
00563 end += 4
00564 (length,) = _struct_I.unpack(str[start:end])
00565 pattern = '<%sd'%length
00566 start = end
00567 end += struct.calcsize(pattern)
00568 self.feedback.error.accelerations = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00569 _x = self
00570 start = end
00571 end += 8
00572 (_x.feedback.error.time_from_start.secs, _x.feedback.error.time_from_start.nsecs,) = _struct_2i.unpack(str[start:end])
00573 return self
00574 except struct.error, e:
00575 raise roslib.message.DeserializationError(e)
00576
00577 _struct_I = roslib.message.struct_I
00578 _struct_3I = struct.Struct("<3I")
00579 _struct_B = struct.Struct("<B")
00580 _struct_2I = struct.Struct("<2I")
00581 _struct_2i = struct.Struct("<2i")