00001 """autogenerated by genmsg_py from PR2GripperEventDetectorAction.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 PR2GripperEventDetectorAction(roslib.message.Message):
00011 _md5sum = "d4e2ee2d04e941280f34bdb366daa9a4"
00012 _type = "pr2_gripper_sensor_msgs/PR2GripperEventDetectorAction"
00013 _has_header = False
00014 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00015
00016 PR2GripperEventDetectorActionGoal action_goal
00017 PR2GripperEventDetectorActionResult action_result
00018 PR2GripperEventDetectorActionFeedback action_feedback
00019
00020 ================================================================================
00021 MSG: pr2_gripper_sensor_msgs/PR2GripperEventDetectorActionGoal
00022 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00023
00024 Header header
00025 actionlib_msgs/GoalID goal_id
00026 PR2GripperEventDetectorGoal 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/PR2GripperEventDetectorGoal
00061 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00062 # Event Detector action used to tell detect events happening on the
00063 # palm mounted accelerometer and finger pressure sensors
00064
00065 #goal
00066 PR2GripperEventDetectorCommand command
00067
00068 ================================================================================
00069 MSG: pr2_gripper_sensor_msgs/PR2GripperEventDetectorCommand
00070 # state variable that defines what events we would like to trigger on
00071 # Leaving this field blank will result in the robot triggering when
00072 # anything touches the sides of the finger or an impact is detected
00073 # with the hand/arm.
00074 int8 trigger_conditions
00075 # definitions for our various trigger_conditions values
00076 # trigger on either acceleration contact or finger sensor side impact
00077 int8 FINGER_SIDE_IMPACT_OR_ACC = 0
00078 # tigger once both slip and acceleration signals occur
00079 int8 SLIP_AND_ACC = 1
00080 # trigger on either slip, acceleration, or finger sensor side impact
00081 int8 FINGER_SIDE_IMPACT_OR_SLIP_OR_ACC = 2
00082 # trigger only on slip information
00083 int8 SLIP = 3
00084 # trigger only on acceleration contact information
00085 int8 ACC = 4
00086
00087
00088 # the amount of acceleration to trigger on (acceleration vector magnitude)
00089 # Units = m/s^2
00090 # The user needs to be concerned here about not setting the trigger too
00091 # low so that is set off by the robot's own motions.
00092 #
00093 # For large rapid motions, say by a motion planner, 5 m/s^2 is a good level
00094 # For small delicate controlled motions this can be set MUCH lower (try 2.0)
00095 #
00096 # NOTE: When moving the gripper joint (opening/closing the grippr)
00097 # the high gearing of the PR2 gripper causes large acceleration vibrations
00098 # which will cause triggering to occur. This is a known drawback of the PR2.
00099 #
00100 # NOTE: Leaving this value blank will result in a 0 m/s^2 trigger. If you
00101 # are using a trigger_conditions value that returns on acceleration contact
00102 # events then it will immediately exceed your trigger and return
00103 float64 acceleration_trigger_magnitude
00104
00105
00106 # the slip detector gain to trigger on (either finger) : try 0.01
00107 # higher values decrease slip sensitivty (to a point)
00108 # lower values increase sensitivity (to a point)
00109 #
00110 # NOTE: Leaving this value blank will result in the most sensitive slip level.
00111 float64 slip_trigger_magnitude
00112 ================================================================================
00113 MSG: pr2_gripper_sensor_msgs/PR2GripperEventDetectorActionResult
00114 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00115
00116 Header header
00117 actionlib_msgs/GoalStatus status
00118 PR2GripperEventDetectorResult result
00119
00120 ================================================================================
00121 MSG: actionlib_msgs/GoalStatus
00122 GoalID goal_id
00123 uint8 status
00124 uint8 PENDING = 0 # The goal has yet to be processed by the action server
00125 uint8 ACTIVE = 1 # The goal is currently being processed by the action server
00126 uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing
00127 # and has since completed its execution (Terminal State)
00128 uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State)
00129 uint8 ABORTED = 4 # The goal was aborted during execution by the action server due
00130 # to some failure (Terminal State)
00131 uint8 REJECTED = 5 # The goal was rejected by the action server without being processed,
00132 # because the goal was unattainable or invalid (Terminal State)
00133 uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing
00134 # and has not yet completed execution
00135 uint8 RECALLING = 7 # The goal received a cancel request before it started executing,
00136 # but the action server has not yet confirmed that the goal is canceled
00137 uint8 RECALLED = 8 # The goal received a cancel request before it started executing
00138 # and was successfully cancelled (Terminal State)
00139 uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be
00140 # sent over the wire by an action server
00141
00142 #Allow for the user to associate a string with GoalStatus for debugging
00143 string text
00144
00145
00146 ================================================================================
00147 MSG: pr2_gripper_sensor_msgs/PR2GripperEventDetectorResult
00148 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00149 #results
00150 PR2GripperEventDetectorData data
00151
00152 ================================================================================
00153 MSG: pr2_gripper_sensor_msgs/PR2GripperEventDetectorData
00154 # Time the data was recorded at
00155 time stamp
00156
00157 # true if the trigger conditions have been met
00158 # (see PR2GripperEventDetectorCommand)
00159 bool trigger_conditions_met
00160
00161 # true if the pressure sensors detected a slip event
00162 # slip events occur when the finger pressure sensors
00163 # high-freq. content exceeds the slip_trigger_magnitude variable
00164 # (see PR2GripperEventDetectorCommand)
00165 bool slip_event
00166
00167 # true if the hand-mounted accelerometer detected a contact acceleration
00168 # acceleration events occur when the palm accelerometer
00169 # high-freq. content exceeds the acc_trigger_magnitude variable
00170 # (see PR2GripperEventDetectorCommand)
00171 bool acceleration_event
00172
00173 # the high-freq acceleration vector that was last seen (x,y,z)
00174 float64[3] acceleration_vector
00175 ================================================================================
00176 MSG: pr2_gripper_sensor_msgs/PR2GripperEventDetectorActionFeedback
00177 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00178
00179 Header header
00180 actionlib_msgs/GoalStatus status
00181 PR2GripperEventDetectorFeedback feedback
00182
00183 ================================================================================
00184 MSG: pr2_gripper_sensor_msgs/PR2GripperEventDetectorFeedback
00185 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00186 # feedback
00187 PR2GripperEventDetectorData data
00188
00189
00190
00191 """
00192 __slots__ = ['action_goal','action_result','action_feedback']
00193 _slot_types = ['pr2_gripper_sensor_msgs/PR2GripperEventDetectorActionGoal','pr2_gripper_sensor_msgs/PR2GripperEventDetectorActionResult','pr2_gripper_sensor_msgs/PR2GripperEventDetectorActionFeedback']
00194
00195 def __init__(self, *args, **kwds):
00196 """
00197 Constructor. Any message fields that are implicitly/explicitly
00198 set to None will be assigned a default value. The recommend
00199 use is keyword arguments as this is more robust to future message
00200 changes. You cannot mix in-order arguments and keyword arguments.
00201
00202 The available fields are:
00203 action_goal,action_result,action_feedback
00204
00205 @param args: complete set of field values, in .msg order
00206 @param kwds: use keyword arguments corresponding to message field names
00207 to set specific fields.
00208 """
00209 if args or kwds:
00210 super(PR2GripperEventDetectorAction, self).__init__(*args, **kwds)
00211
00212 if self.action_goal is None:
00213 self.action_goal = pr2_gripper_sensor_msgs.msg.PR2GripperEventDetectorActionGoal()
00214 if self.action_result is None:
00215 self.action_result = pr2_gripper_sensor_msgs.msg.PR2GripperEventDetectorActionResult()
00216 if self.action_feedback is None:
00217 self.action_feedback = pr2_gripper_sensor_msgs.msg.PR2GripperEventDetectorActionFeedback()
00218 else:
00219 self.action_goal = pr2_gripper_sensor_msgs.msg.PR2GripperEventDetectorActionGoal()
00220 self.action_result = pr2_gripper_sensor_msgs.msg.PR2GripperEventDetectorActionResult()
00221 self.action_feedback = pr2_gripper_sensor_msgs.msg.PR2GripperEventDetectorActionFeedback()
00222
00223 def _get_types(self):
00224 """
00225 internal API method
00226 """
00227 return self._slot_types
00228
00229 def serialize(self, buff):
00230 """
00231 serialize message into buffer
00232 @param buff: buffer
00233 @type buff: StringIO
00234 """
00235 try:
00236 _x = self
00237 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00238 _x = self.action_goal.header.frame_id
00239 length = len(_x)
00240 buff.write(struct.pack('<I%ss'%length, length, _x))
00241 _x = self
00242 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00243 _x = self.action_goal.goal_id.id
00244 length = len(_x)
00245 buff.write(struct.pack('<I%ss'%length, length, _x))
00246 _x = self
00247 buff.write(_struct_b2d3I.pack(_x.action_goal.goal.command.trigger_conditions, _x.action_goal.goal.command.acceleration_trigger_magnitude, _x.action_goal.goal.command.slip_trigger_magnitude, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00248 _x = self.action_result.header.frame_id
00249 length = len(_x)
00250 buff.write(struct.pack('<I%ss'%length, length, _x))
00251 _x = self
00252 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00253 _x = self.action_result.status.goal_id.id
00254 length = len(_x)
00255 buff.write(struct.pack('<I%ss'%length, length, _x))
00256 buff.write(_struct_B.pack(self.action_result.status.status))
00257 _x = self.action_result.status.text
00258 length = len(_x)
00259 buff.write(struct.pack('<I%ss'%length, length, _x))
00260 _x = self
00261 buff.write(_struct_2I3B.pack(_x.action_result.result.data.stamp.secs, _x.action_result.result.data.stamp.nsecs, _x.action_result.result.data.trigger_conditions_met, _x.action_result.result.data.slip_event, _x.action_result.result.data.acceleration_event))
00262 buff.write(_struct_3d.pack(*self.action_result.result.data.acceleration_vector))
00263 _x = self
00264 buff.write(_struct_3I.pack(_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00265 _x = self.action_feedback.header.frame_id
00266 length = len(_x)
00267 buff.write(struct.pack('<I%ss'%length, length, _x))
00268 _x = self
00269 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00270 _x = self.action_feedback.status.goal_id.id
00271 length = len(_x)
00272 buff.write(struct.pack('<I%ss'%length, length, _x))
00273 buff.write(_struct_B.pack(self.action_feedback.status.status))
00274 _x = self.action_feedback.status.text
00275 length = len(_x)
00276 buff.write(struct.pack('<I%ss'%length, length, _x))
00277 _x = self
00278 buff.write(_struct_2I3B.pack(_x.action_feedback.feedback.data.stamp.secs, _x.action_feedback.feedback.data.stamp.nsecs, _x.action_feedback.feedback.data.trigger_conditions_met, _x.action_feedback.feedback.data.slip_event, _x.action_feedback.feedback.data.acceleration_event))
00279 buff.write(_struct_3d.pack(*self.action_feedback.feedback.data.acceleration_vector))
00280 except struct.error, se: self._check_types(se)
00281 except TypeError, te: self._check_types(te)
00282
00283 def deserialize(self, str):
00284 """
00285 unpack serialized message in str into this message instance
00286 @param str: byte array of serialized message
00287 @type str: str
00288 """
00289 try:
00290 if self.action_goal is None:
00291 self.action_goal = pr2_gripper_sensor_msgs.msg.PR2GripperEventDetectorActionGoal()
00292 if self.action_result is None:
00293 self.action_result = pr2_gripper_sensor_msgs.msg.PR2GripperEventDetectorActionResult()
00294 if self.action_feedback is None:
00295 self.action_feedback = pr2_gripper_sensor_msgs.msg.PR2GripperEventDetectorActionFeedback()
00296 end = 0
00297 _x = self
00298 start = end
00299 end += 12
00300 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00301 start = end
00302 end += 4
00303 (length,) = _struct_I.unpack(str[start:end])
00304 start = end
00305 end += length
00306 self.action_goal.header.frame_id = str[start:end]
00307 _x = self
00308 start = end
00309 end += 8
00310 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00311 start = end
00312 end += 4
00313 (length,) = _struct_I.unpack(str[start:end])
00314 start = end
00315 end += length
00316 self.action_goal.goal_id.id = str[start:end]
00317 _x = self
00318 start = end
00319 end += 29
00320 (_x.action_goal.goal.command.trigger_conditions, _x.action_goal.goal.command.acceleration_trigger_magnitude, _x.action_goal.goal.command.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])
00321 start = end
00322 end += 4
00323 (length,) = _struct_I.unpack(str[start:end])
00324 start = end
00325 end += length
00326 self.action_result.header.frame_id = str[start:end]
00327 _x = self
00328 start = end
00329 end += 8
00330 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00331 start = end
00332 end += 4
00333 (length,) = _struct_I.unpack(str[start:end])
00334 start = end
00335 end += length
00336 self.action_result.status.goal_id.id = str[start:end]
00337 start = end
00338 end += 1
00339 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00340 start = end
00341 end += 4
00342 (length,) = _struct_I.unpack(str[start:end])
00343 start = end
00344 end += length
00345 self.action_result.status.text = str[start:end]
00346 _x = self
00347 start = end
00348 end += 11
00349 (_x.action_result.result.data.stamp.secs, _x.action_result.result.data.stamp.nsecs, _x.action_result.result.data.trigger_conditions_met, _x.action_result.result.data.slip_event, _x.action_result.result.data.acceleration_event,) = _struct_2I3B.unpack(str[start:end])
00350 self.action_result.result.data.trigger_conditions_met = bool(self.action_result.result.data.trigger_conditions_met)
00351 self.action_result.result.data.slip_event = bool(self.action_result.result.data.slip_event)
00352 self.action_result.result.data.acceleration_event = bool(self.action_result.result.data.acceleration_event)
00353 start = end
00354 end += 24
00355 self.action_result.result.data.acceleration_vector = _struct_3d.unpack(str[start:end])
00356 _x = self
00357 start = end
00358 end += 12
00359 (_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00360 start = end
00361 end += 4
00362 (length,) = _struct_I.unpack(str[start:end])
00363 start = end
00364 end += length
00365 self.action_feedback.header.frame_id = str[start:end]
00366 _x = self
00367 start = end
00368 end += 8
00369 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00370 start = end
00371 end += 4
00372 (length,) = _struct_I.unpack(str[start:end])
00373 start = end
00374 end += length
00375 self.action_feedback.status.goal_id.id = str[start:end]
00376 start = end
00377 end += 1
00378 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00379 start = end
00380 end += 4
00381 (length,) = _struct_I.unpack(str[start:end])
00382 start = end
00383 end += length
00384 self.action_feedback.status.text = str[start:end]
00385 _x = self
00386 start = end
00387 end += 11
00388 (_x.action_feedback.feedback.data.stamp.secs, _x.action_feedback.feedback.data.stamp.nsecs, _x.action_feedback.feedback.data.trigger_conditions_met, _x.action_feedback.feedback.data.slip_event, _x.action_feedback.feedback.data.acceleration_event,) = _struct_2I3B.unpack(str[start:end])
00389 self.action_feedback.feedback.data.trigger_conditions_met = bool(self.action_feedback.feedback.data.trigger_conditions_met)
00390 self.action_feedback.feedback.data.slip_event = bool(self.action_feedback.feedback.data.slip_event)
00391 self.action_feedback.feedback.data.acceleration_event = bool(self.action_feedback.feedback.data.acceleration_event)
00392 start = end
00393 end += 24
00394 self.action_feedback.feedback.data.acceleration_vector = _struct_3d.unpack(str[start:end])
00395 return self
00396 except struct.error, e:
00397 raise roslib.message.DeserializationError(e)
00398
00399
00400 def serialize_numpy(self, buff, numpy):
00401 """
00402 serialize message with numpy array types into buffer
00403 @param buff: buffer
00404 @type buff: StringIO
00405 @param numpy: numpy python module
00406 @type numpy module
00407 """
00408 try:
00409 _x = self
00410 buff.write(_struct_3I.pack(_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs))
00411 _x = self.action_goal.header.frame_id
00412 length = len(_x)
00413 buff.write(struct.pack('<I%ss'%length, length, _x))
00414 _x = self
00415 buff.write(_struct_2I.pack(_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs))
00416 _x = self.action_goal.goal_id.id
00417 length = len(_x)
00418 buff.write(struct.pack('<I%ss'%length, length, _x))
00419 _x = self
00420 buff.write(_struct_b2d3I.pack(_x.action_goal.goal.command.trigger_conditions, _x.action_goal.goal.command.acceleration_trigger_magnitude, _x.action_goal.goal.command.slip_trigger_magnitude, _x.action_result.header.seq, _x.action_result.header.stamp.secs, _x.action_result.header.stamp.nsecs))
00421 _x = self.action_result.header.frame_id
00422 length = len(_x)
00423 buff.write(struct.pack('<I%ss'%length, length, _x))
00424 _x = self
00425 buff.write(_struct_2I.pack(_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs))
00426 _x = self.action_result.status.goal_id.id
00427 length = len(_x)
00428 buff.write(struct.pack('<I%ss'%length, length, _x))
00429 buff.write(_struct_B.pack(self.action_result.status.status))
00430 _x = self.action_result.status.text
00431 length = len(_x)
00432 buff.write(struct.pack('<I%ss'%length, length, _x))
00433 _x = self
00434 buff.write(_struct_2I3B.pack(_x.action_result.result.data.stamp.secs, _x.action_result.result.data.stamp.nsecs, _x.action_result.result.data.trigger_conditions_met, _x.action_result.result.data.slip_event, _x.action_result.result.data.acceleration_event))
00435 buff.write(self.action_result.result.data.acceleration_vector.tostring())
00436 _x = self
00437 buff.write(_struct_3I.pack(_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs))
00438 _x = self.action_feedback.header.frame_id
00439 length = len(_x)
00440 buff.write(struct.pack('<I%ss'%length, length, _x))
00441 _x = self
00442 buff.write(_struct_2I.pack(_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs))
00443 _x = self.action_feedback.status.goal_id.id
00444 length = len(_x)
00445 buff.write(struct.pack('<I%ss'%length, length, _x))
00446 buff.write(_struct_B.pack(self.action_feedback.status.status))
00447 _x = self.action_feedback.status.text
00448 length = len(_x)
00449 buff.write(struct.pack('<I%ss'%length, length, _x))
00450 _x = self
00451 buff.write(_struct_2I3B.pack(_x.action_feedback.feedback.data.stamp.secs, _x.action_feedback.feedback.data.stamp.nsecs, _x.action_feedback.feedback.data.trigger_conditions_met, _x.action_feedback.feedback.data.slip_event, _x.action_feedback.feedback.data.acceleration_event))
00452 buff.write(self.action_feedback.feedback.data.acceleration_vector.tostring())
00453 except struct.error, se: self._check_types(se)
00454 except TypeError, te: self._check_types(te)
00455
00456 def deserialize_numpy(self, str, numpy):
00457 """
00458 unpack serialized message in str into this message instance using numpy for array types
00459 @param str: byte array of serialized message
00460 @type str: str
00461 @param numpy: numpy python module
00462 @type numpy: module
00463 """
00464 try:
00465 if self.action_goal is None:
00466 self.action_goal = pr2_gripper_sensor_msgs.msg.PR2GripperEventDetectorActionGoal()
00467 if self.action_result is None:
00468 self.action_result = pr2_gripper_sensor_msgs.msg.PR2GripperEventDetectorActionResult()
00469 if self.action_feedback is None:
00470 self.action_feedback = pr2_gripper_sensor_msgs.msg.PR2GripperEventDetectorActionFeedback()
00471 end = 0
00472 _x = self
00473 start = end
00474 end += 12
00475 (_x.action_goal.header.seq, _x.action_goal.header.stamp.secs, _x.action_goal.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00476 start = end
00477 end += 4
00478 (length,) = _struct_I.unpack(str[start:end])
00479 start = end
00480 end += length
00481 self.action_goal.header.frame_id = str[start:end]
00482 _x = self
00483 start = end
00484 end += 8
00485 (_x.action_goal.goal_id.stamp.secs, _x.action_goal.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00486 start = end
00487 end += 4
00488 (length,) = _struct_I.unpack(str[start:end])
00489 start = end
00490 end += length
00491 self.action_goal.goal_id.id = str[start:end]
00492 _x = self
00493 start = end
00494 end += 29
00495 (_x.action_goal.goal.command.trigger_conditions, _x.action_goal.goal.command.acceleration_trigger_magnitude, _x.action_goal.goal.command.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])
00496 start = end
00497 end += 4
00498 (length,) = _struct_I.unpack(str[start:end])
00499 start = end
00500 end += length
00501 self.action_result.header.frame_id = str[start:end]
00502 _x = self
00503 start = end
00504 end += 8
00505 (_x.action_result.status.goal_id.stamp.secs, _x.action_result.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00506 start = end
00507 end += 4
00508 (length,) = _struct_I.unpack(str[start:end])
00509 start = end
00510 end += length
00511 self.action_result.status.goal_id.id = str[start:end]
00512 start = end
00513 end += 1
00514 (self.action_result.status.status,) = _struct_B.unpack(str[start:end])
00515 start = end
00516 end += 4
00517 (length,) = _struct_I.unpack(str[start:end])
00518 start = end
00519 end += length
00520 self.action_result.status.text = str[start:end]
00521 _x = self
00522 start = end
00523 end += 11
00524 (_x.action_result.result.data.stamp.secs, _x.action_result.result.data.stamp.nsecs, _x.action_result.result.data.trigger_conditions_met, _x.action_result.result.data.slip_event, _x.action_result.result.data.acceleration_event,) = _struct_2I3B.unpack(str[start:end])
00525 self.action_result.result.data.trigger_conditions_met = bool(self.action_result.result.data.trigger_conditions_met)
00526 self.action_result.result.data.slip_event = bool(self.action_result.result.data.slip_event)
00527 self.action_result.result.data.acceleration_event = bool(self.action_result.result.data.acceleration_event)
00528 start = end
00529 end += 24
00530 self.action_result.result.data.acceleration_vector = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=3)
00531 _x = self
00532 start = end
00533 end += 12
00534 (_x.action_feedback.header.seq, _x.action_feedback.header.stamp.secs, _x.action_feedback.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00535 start = end
00536 end += 4
00537 (length,) = _struct_I.unpack(str[start:end])
00538 start = end
00539 end += length
00540 self.action_feedback.header.frame_id = str[start:end]
00541 _x = self
00542 start = end
00543 end += 8
00544 (_x.action_feedback.status.goal_id.stamp.secs, _x.action_feedback.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00545 start = end
00546 end += 4
00547 (length,) = _struct_I.unpack(str[start:end])
00548 start = end
00549 end += length
00550 self.action_feedback.status.goal_id.id = str[start:end]
00551 start = end
00552 end += 1
00553 (self.action_feedback.status.status,) = _struct_B.unpack(str[start:end])
00554 start = end
00555 end += 4
00556 (length,) = _struct_I.unpack(str[start:end])
00557 start = end
00558 end += length
00559 self.action_feedback.status.text = str[start:end]
00560 _x = self
00561 start = end
00562 end += 11
00563 (_x.action_feedback.feedback.data.stamp.secs, _x.action_feedback.feedback.data.stamp.nsecs, _x.action_feedback.feedback.data.trigger_conditions_met, _x.action_feedback.feedback.data.slip_event, _x.action_feedback.feedback.data.acceleration_event,) = _struct_2I3B.unpack(str[start:end])
00564 self.action_feedback.feedback.data.trigger_conditions_met = bool(self.action_feedback.feedback.data.trigger_conditions_met)
00565 self.action_feedback.feedback.data.slip_event = bool(self.action_feedback.feedback.data.slip_event)
00566 self.action_feedback.feedback.data.acceleration_event = bool(self.action_feedback.feedback.data.acceleration_event)
00567 start = end
00568 end += 24
00569 self.action_feedback.feedback.data.acceleration_vector = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=3)
00570 return self
00571 except struct.error, e:
00572 raise roslib.message.DeserializationError(e)
00573
00574 _struct_I = roslib.message.struct_I
00575 _struct_B = struct.Struct("<B")
00576 _struct_2I3B = struct.Struct("<2I3B")
00577 _struct_b2d3I = struct.Struct("<b2d3I")
00578 _struct_3I = struct.Struct("<3I")
00579 _struct_2I = struct.Struct("<2I")
00580 _struct_3d = struct.Struct("<3d")