00001 """autogenerated by genmsg_py from PR2GripperReleaseAction.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import roslib.rostime
00006 import actionlib_msgs.msg
00007 import pr2_gripper_sensor_msgs.msg
00008 import std_msgs.msg
00009
00010 class PR2GripperReleaseAction(roslib.message.Message):
00011 _md5sum = "c3c9b6394f2bb7d0d9e5ed002d9a759a"
00012 _type = "pr2_gripper_sensor_msgs/PR2GripperReleaseAction"
00013 _has_header = False
00014 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00015
00016 PR2GripperReleaseActionGoal action_goal
00017 PR2GripperReleaseActionResult action_result
00018 PR2GripperReleaseActionFeedback action_feedback
00019
00020 ================================================================================
00021 MSG: pr2_gripper_sensor_msgs/PR2GripperReleaseActionGoal
00022 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00023
00024 Header header
00025 actionlib_msgs/GoalID goal_id
00026 PR2GripperReleaseGoal goal
00027
00028 ================================================================================
00029 MSG: std_msgs/Header
00030 # Standard metadata for higher-level stamped data types.
00031 # This is generally used to communicate timestamped data
00032 # in a particular coordinate frame.
00033 #
00034 # sequence ID: consecutively increasing ID
00035 uint32 seq
00036 #Two-integer timestamp that is expressed as:
00037 # * stamp.secs: seconds (stamp_secs) since epoch
00038 # * stamp.nsecs: nanoseconds since stamp_secs
00039 # time-handling sugar is provided by the client library
00040 time stamp
00041 #Frame this data is associated with
00042 # 0: no frame
00043 # 1: global frame
00044 string frame_id
00045
00046 ================================================================================
00047 MSG: actionlib_msgs/GoalID
00048 # The stamp should store the time at which this goal was requested.
00049 # It is used by an action server when it tries to preempt all
00050 # goals that were requested before a certain time
00051 time stamp
00052
00053 # The id provides a way to associate feedback and
00054 # result message with specific goal requests. The id
00055 # specified must be unique.
00056 string id
00057
00058
00059 ================================================================================
00060 MSG: pr2_gripper_sensor_msgs/PR2GripperReleaseGoal
00061 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00062 #goal
00063 PR2GripperReleaseCommand command
00064
00065 ================================================================================
00066 MSG: pr2_gripper_sensor_msgs/PR2GripperReleaseCommand
00067 # the event conditions we would like to trigger the robot to release on
00068 PR2GripperEventDetectorCommand event
00069 ================================================================================
00070 MSG: pr2_gripper_sensor_msgs/PR2GripperEventDetectorCommand
00071 # state variable that defines what events we would like to trigger on
00072 # Leaving this field blank will result in the robot triggering when
00073 # anything touches the sides of the finger or an impact is detected
00074 # with the hand/arm.
00075 int8 trigger_conditions
00076 # definitions for our various trigger_conditions values
00077 # trigger on either acceleration contact or finger sensor side impact
00078 int8 FINGER_SIDE_IMPACT_OR_ACC = 0
00079 # tigger once both slip and acceleration signals occur
00080 int8 SLIP_AND_ACC = 1
00081 # trigger on either slip, acceleration, or finger sensor side impact
00082 int8 FINGER_SIDE_IMPACT_OR_SLIP_OR_ACC = 2
00083 # trigger only on slip information
00084 int8 SLIP = 3
00085 # trigger only on acceleration contact information
00086 int8 ACC = 4
00087
00088
00089 # the amount of acceleration to trigger on (acceleration vector magnitude)
00090 # Units = m/s^2
00091 # The user needs to be concerned here about not setting the trigger too
00092 # low so that is set off by the robot's own motions.
00093 #
00094 # For large rapid motions, say by a motion planner, 5 m/s^2 is a good level
00095 # For small delicate controlled motions this can be set MUCH lower (try 2.0)
00096 #
00097 # NOTE: When moving the gripper joint (opening/closing the grippr)
00098 # the high gearing of the PR2 gripper causes large acceleration vibrations
00099 # which will cause triggering to occur. This is a known drawback of the PR2.
00100 #
00101 # NOTE: Leaving this value blank will result in a 0 m/s^2 trigger. If you
00102 # are using a trigger_conditions value that returns on acceleration contact
00103 # events then it will immediately exceed your trigger and return
00104 float64 acceleration_trigger_magnitude
00105
00106
00107 # the slip detector gain to trigger on (either finger) : try 0.01
00108 # higher values decrease slip sensitivty (to a point)
00109 # lower values increase sensitivity (to a point)
00110 #
00111 # NOTE: Leaving this value blank will result in the most sensitive slip level.
00112 float64 slip_trigger_magnitude
00113 ================================================================================
00114 MSG: pr2_gripper_sensor_msgs/PR2GripperReleaseActionResult
00115 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00116
00117 Header header
00118 actionlib_msgs/GoalStatus status
00119 PR2GripperReleaseResult result
00120
00121 ================================================================================
00122 MSG: actionlib_msgs/GoalStatus
00123 GoalID goal_id
00124 uint8 status
00125 uint8 PENDING = 0 # The goal has yet to be processed by the action server
00126 uint8 ACTIVE = 1 # The goal is currently being processed by the action server
00127 uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing
00128 # and has since completed its execution (Terminal State)
00129 uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State)
00130 uint8 ABORTED = 4 # The goal was aborted during execution by the action server due
00131 # to some failure (Terminal State)
00132 uint8 REJECTED = 5 # The goal was rejected by the action server without being processed,
00133 # because the goal was unattainable or invalid (Terminal State)
00134 uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing
00135 # and has not yet completed execution
00136 uint8 RECALLING = 7 # The goal received a cancel request before it started executing,
00137 # but the action server has not yet confirmed that the goal is canceled
00138 uint8 RECALLED = 8 # The goal received a cancel request before it started executing
00139 # and was successfully cancelled (Terminal State)
00140 uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be
00141 # sent over the wire by an action server
00142
00143 #Allow for the user to associate a string with GoalStatus for debugging
00144 string text
00145
00146
00147 ================================================================================
00148 MSG: pr2_gripper_sensor_msgs/PR2GripperReleaseResult
00149 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00150 #result
00151 PR2GripperReleaseData data
00152
00153 ================================================================================
00154 MSG: pr2_gripper_sensor_msgs/PR2GripperReleaseData
00155 # the control state of our realtime controller
00156 PR2GripperSensorRTState rtstate
00157 ================================================================================
00158 MSG: pr2_gripper_sensor_msgs/PR2GripperSensorRTState
00159 # the control state of our realtime controller
00160 int8 realtime_controller_state
00161
00162 # predefined values to indicate our realtime_controller_state
00163 int8 DISABLED = 0
00164 int8 POSITION_SERVO = 3
00165 int8 FORCE_SERVO = 4
00166 int8 FIND_CONTACT = 5
00167 int8 SLIP_SERVO = 6
00168 ================================================================================
00169 MSG: pr2_gripper_sensor_msgs/PR2GripperReleaseActionFeedback
00170 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00171
00172 Header header
00173 actionlib_msgs/GoalStatus status
00174 PR2GripperReleaseFeedback feedback
00175
00176 ================================================================================
00177 MSG: pr2_gripper_sensor_msgs/PR2GripperReleaseFeedback
00178 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00179
00180 #feedback
00181 PR2GripperReleaseData data
00182
00183
00184 """
00185 __slots__ = ['action_goal','action_result','action_feedback']
00186 _slot_types = ['pr2_gripper_sensor_msgs/PR2GripperReleaseActionGoal','pr2_gripper_sensor_msgs/PR2GripperReleaseActionResult','pr2_gripper_sensor_msgs/PR2GripperReleaseActionFeedback']
00187
00188 def __init__(self, *args, **kwds):
00189 """
00190 Constructor. Any message fields that are implicitly/explicitly
00191 set to None will be assigned a default value. The recommend
00192 use is keyword arguments as this is more robust to future message
00193 changes. You cannot mix in-order arguments and keyword arguments.
00194
00195 The available fields are:
00196 action_goal,action_result,action_feedback
00197
00198 @param args: complete set of field values, in .msg order
00199 @param kwds: use keyword arguments corresponding to message field names
00200 to set specific fields.
00201 """
00202 if args or kwds:
00203 super(PR2GripperReleaseAction, self).__init__(*args, **kwds)
00204
00205 if self.action_goal is None:
00206 self.action_goal = pr2_gripper_sensor_msgs.msg.PR2GripperReleaseActionGoal()
00207 if self.action_result is None:
00208 self.action_result = pr2_gripper_sensor_msgs.msg.PR2GripperReleaseActionResult()
00209 if self.action_feedback is None:
00210 self.action_feedback = pr2_gripper_sensor_msgs.msg.PR2GripperReleaseActionFeedback()
00211 else:
00212 self.action_goal = pr2_gripper_sensor_msgs.msg.PR2GripperReleaseActionGoal()
00213 self.action_result = pr2_gripper_sensor_msgs.msg.PR2GripperReleaseActionResult()
00214 self.action_feedback = pr2_gripper_sensor_msgs.msg.PR2GripperReleaseActionFeedback()
00215
00216 def _get_types(self):
00217 """
00218 internal API method
00219 """
00220 return self._slot_types
00221
00222 def serialize(self, buff):
00223 """
00224 serialize message into buffer
00225 @param buff: buffer
00226 @type buff: StringIO
00227 """
00228 try:
00229 _x = self
00230 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00231 _x = self.action_goal.header.frame_id
00232 length = len(_x)
00233 buff.write(struct.pack('<I%ss'%length, length, _x))
00234 _x = self
00235 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00236 _x = self.action_goal.goal_id.id
00237 length = len(_x)
00238 buff.write(struct.pack('<I%ss'%length, length, _x))
00239 _x = self
00240 buff.write(_struct_b2d3I.pack(_x.action_goal.goal.command.event.trigger_conditions, _x.action_goal.goal.command.event.acceleration_trigger_magnitude, _x.action_goal.goal.command.event.slip_trigger_magnitude, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00241 _x = self.action_result.header.frame_id
00242 length = len(_x)
00243 buff.write(struct.pack('<I%ss'%length, length, _x))
00244 _x = self
00245 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00246 _x = self.action_result.status.goal_id.id
00247 length = len(_x)
00248 buff.write(struct.pack('<I%ss'%length, length, _x))
00249 buff.write(_struct_B.pack(self.action_result.status.status))
00250 _x = self.action_result.status.text
00251 length = len(_x)
00252 buff.write(struct.pack('<I%ss'%length, length, _x))
00253 _x = self
00254 buff.write(_struct_b3I.pack(_x.action_result.result.data.rtstate.realtime_controller_state, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00255 _x = self.action_feedback.header.frame_id
00256 length = len(_x)
00257 buff.write(struct.pack('<I%ss'%length, length, _x))
00258 _x = self
00259 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00260 _x = self.action_feedback.status.goal_id.id
00261 length = len(_x)
00262 buff.write(struct.pack('<I%ss'%length, length, _x))
00263 buff.write(_struct_B.pack(self.action_feedback.status.status))
00264 _x = self.action_feedback.status.text
00265 length = len(_x)
00266 buff.write(struct.pack('<I%ss'%length, length, _x))
00267 buff.write(_struct_b.pack(self.action_feedback.feedback.data.rtstate.realtime_controller_state))
00268 except struct.error, se: self._check_types(se)
00269 except TypeError, te: self._check_types(te)
00270
00271 def deserialize(self, str):
00272 """
00273 unpack serialized message in str into this message instance
00274 @param str: byte array of serialized message
00275 @type str: str
00276 """
00277 try:
00278 if self.action_goal is None:
00279 self.action_goal = pr2_gripper_sensor_msgs.msg.PR2GripperReleaseActionGoal()
00280 if self.action_result is None:
00281 self.action_result = pr2_gripper_sensor_msgs.msg.PR2GripperReleaseActionResult()
00282 if self.action_feedback is None:
00283 self.action_feedback = pr2_gripper_sensor_msgs.msg.PR2GripperReleaseActionFeedback()
00284 end = 0
00285 _x = self
00286 start = end
00287 end += 12
00288 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00289 start = end
00290 end += 4
00291 (length,) = _struct_I.unpack(str[start:end])
00292 start = end
00293 end += length
00294 self.action_goal.header.frame_id = str[start:end]
00295 _x = self
00296 start = end
00297 end += 8
00298 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00299 start = end
00300 end += 4
00301 (length,) = _struct_I.unpack(str[start:end])
00302 start = end
00303 end += length
00304 self.action_goal.goal_id.id = str[start:end]
00305 _x = self
00306 start = end
00307 end += 29
00308 (_x.action_goal.goal.command.event.trigger_conditions, _x.action_goal.goal.command.event.acceleration_trigger_magnitude, _x.action_goal.goal.command.event.slip_trigger_magnitude, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_b2d3I.unpack(str[start:end])
00309 start = end
00310 end += 4
00311 (length,) = _struct_I.unpack(str[start:end])
00312 start = end
00313 end += length
00314 self.action_result.header.frame_id = str[start:end]
00315 _x = self
00316 start = end
00317 end += 8
00318 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00319 start = end
00320 end += 4
00321 (length,) = _struct_I.unpack(str[start:end])
00322 start = end
00323 end += length
00324 self.action_result.status.goal_id.id = str[start:end]
00325 start = end
00326 end += 1
00327 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00328 start = end
00329 end += 4
00330 (length,) = _struct_I.unpack(str[start:end])
00331 start = end
00332 end += length
00333 self.action_result.status.text = str[start:end]
00334 _x = self
00335 start = end
00336 end += 13
00337 (_x.action_result.result.data.rtstate.realtime_controller_state, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_b3I.unpack(str[start:end])
00338 start = end
00339 end += 4
00340 (length,) = _struct_I.unpack(str[start:end])
00341 start = end
00342 end += length
00343 self.action_feedback.header.frame_id = str[start:end]
00344 _x = self
00345 start = end
00346 end += 8
00347 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00348 start = end
00349 end += 4
00350 (length,) = _struct_I.unpack(str[start:end])
00351 start = end
00352 end += length
00353 self.action_feedback.status.goal_id.id = str[start:end]
00354 start = end
00355 end += 1
00356 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00357 start = end
00358 end += 4
00359 (length,) = _struct_I.unpack(str[start:end])
00360 start = end
00361 end += length
00362 self.action_feedback.status.text = str[start:end]
00363 start = end
00364 end += 1
00365 (self.action_feedback.feedback.data.rtstate.realtime_controller_state,) = _struct_b.unpack(str[start:end])
00366 return self
00367 except struct.error, e:
00368 raise roslib.message.DeserializationError(e)
00369
00370
00371 def serialize_numpy(self, buff, numpy):
00372 """
00373 serialize message with numpy array types into buffer
00374 @param buff: buffer
00375 @type buff: StringIO
00376 @param numpy: numpy python module
00377 @type numpy module
00378 """
00379 try:
00380 _x = self
00381 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00382 _x = self.action_goal.header.frame_id
00383 length = len(_x)
00384 buff.write(struct.pack('<I%ss'%length, length, _x))
00385 _x = self
00386 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00387 _x = self.action_goal.goal_id.id
00388 length = len(_x)
00389 buff.write(struct.pack('<I%ss'%length, length, _x))
00390 _x = self
00391 buff.write(_struct_b2d3I.pack(_x.action_goal.goal.command.event.trigger_conditions, _x.action_goal.goal.command.event.acceleration_trigger_magnitude, _x.action_goal.goal.command.event.slip_trigger_magnitude, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00392 _x = self.action_result.header.frame_id
00393 length = len(_x)
00394 buff.write(struct.pack('<I%ss'%length, length, _x))
00395 _x = self
00396 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00397 _x = self.action_result.status.goal_id.id
00398 length = len(_x)
00399 buff.write(struct.pack('<I%ss'%length, length, _x))
00400 buff.write(_struct_B.pack(self.action_result.status.status))
00401 _x = self.action_result.status.text
00402 length = len(_x)
00403 buff.write(struct.pack('<I%ss'%length, length, _x))
00404 _x = self
00405 buff.write(_struct_b3I.pack(_x.action_result.result.data.rtstate.realtime_controller_state, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00406 _x = self.action_feedback.header.frame_id
00407 length = len(_x)
00408 buff.write(struct.pack('<I%ss'%length, length, _x))
00409 _x = self
00410 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00411 _x = self.action_feedback.status.goal_id.id
00412 length = len(_x)
00413 buff.write(struct.pack('<I%ss'%length, length, _x))
00414 buff.write(_struct_B.pack(self.action_feedback.status.status))
00415 _x = self.action_feedback.status.text
00416 length = len(_x)
00417 buff.write(struct.pack('<I%ss'%length, length, _x))
00418 buff.write(_struct_b.pack(self.action_feedback.feedback.data.rtstate.realtime_controller_state))
00419 except struct.error, se: self._check_types(se)
00420 except TypeError, te: self._check_types(te)
00421
00422 def deserialize_numpy(self, str, numpy):
00423 """
00424 unpack serialized message in str into this message instance using numpy for array types
00425 @param str: byte array of serialized message
00426 @type str: str
00427 @param numpy: numpy python module
00428 @type numpy: module
00429 """
00430 try:
00431 if self.action_goal is None:
00432 self.action_goal = pr2_gripper_sensor_msgs.msg.PR2GripperReleaseActionGoal()
00433 if self.action_result is None:
00434 self.action_result = pr2_gripper_sensor_msgs.msg.PR2GripperReleaseActionResult()
00435 if self.action_feedback is None:
00436 self.action_feedback = pr2_gripper_sensor_msgs.msg.PR2GripperReleaseActionFeedback()
00437 end = 0
00438 _x = self
00439 start = end
00440 end += 12
00441 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00442 start = end
00443 end += 4
00444 (length,) = _struct_I.unpack(str[start:end])
00445 start = end
00446 end += length
00447 self.action_goal.header.frame_id = str[start:end]
00448 _x = self
00449 start = end
00450 end += 8
00451 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00452 start = end
00453 end += 4
00454 (length,) = _struct_I.unpack(str[start:end])
00455 start = end
00456 end += length
00457 self.action_goal.goal_id.id = str[start:end]
00458 _x = self
00459 start = end
00460 end += 29
00461 (_x.action_goal.goal.command.event.trigger_conditions, _x.action_goal.goal.command.event.acceleration_trigger_magnitude, _x.action_goal.goal.command.event.slip_trigger_magnitude, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs,) = _struct_b2d3I.unpack(str[start:end])
00462 start = end
00463 end += 4
00464 (length,) = _struct_I.unpack(str[start:end])
00465 start = end
00466 end += length
00467 self.action_result.header.frame_id = str[start:end]
00468 _x = self
00469 start = end
00470 end += 8
00471 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00472 start = end
00473 end += 4
00474 (length,) = _struct_I.unpack(str[start:end])
00475 start = end
00476 end += length
00477 self.action_result.status.goal_id.id = str[start:end]
00478 start = end
00479 end += 1
00480 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00481 start = end
00482 end += 4
00483 (length,) = _struct_I.unpack(str[start:end])
00484 start = end
00485 end += length
00486 self.action_result.status.text = str[start:end]
00487 _x = self
00488 start = end
00489 end += 13
00490 (_x.action_result.result.data.rtstate.realtime_controller_state, _x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_b3I.unpack(str[start:end])
00491 start = end
00492 end += 4
00493 (length,) = _struct_I.unpack(str[start:end])
00494 start = end
00495 end += length
00496 self.action_feedback.header.frame_id = str[start:end]
00497 _x = self
00498 start = end
00499 end += 8
00500 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00501 start = end
00502 end += 4
00503 (length,) = _struct_I.unpack(str[start:end])
00504 start = end
00505 end += length
00506 self.action_feedback.status.goal_id.id = str[start:end]
00507 start = end
00508 end += 1
00509 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00510 start = end
00511 end += 4
00512 (length,) = _struct_I.unpack(str[start:end])
00513 start = end
00514 end += length
00515 self.action_feedback.status.text = str[start:end]
00516 start = end
00517 end += 1
00518 (self.action_feedback.feedback.data.rtstate.realtime_controller_state,) = _struct_b.unpack(str[start:end])
00519 return self
00520 except struct.error, e:
00521 raise roslib.message.DeserializationError(e)
00522
00523 _struct_I = roslib.message.struct_I
00524 _struct_B = struct.Struct("<B")
00525 _struct_b2d3I = struct.Struct("<b2d3I")
00526 _struct_3I = struct.Struct("<3I")
00527 _struct_b = struct.Struct("<b")
00528 _struct_b3I = struct.Struct("<b3I")
00529 _struct_2I = struct.Struct("<2I")