00001 """autogenerated by genmsg_py from MoveArmResult.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import arm_navigation_msgs.msg
00006 import geometry_msgs.msg
00007 import std_msgs.msg
00008
00009 class MoveArmResult(roslib.message.Message):
00010 _md5sum = "3229301226a0605e3ffc9dfdaeac662f"
00011 _type = "arm_navigation_msgs/MoveArmResult"
00012 _has_header = False
00013 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00014 # An error code reflecting what went wrong
00015 ArmNavigationErrorCodes error_code
00016
00017 ContactInformation[] contacts
00018
00019 ================================================================================
00020 MSG: arm_navigation_msgs/ArmNavigationErrorCodes
00021 int32 val
00022
00023 # overall behavior
00024 int32 PLANNING_FAILED=-1
00025 int32 SUCCESS=1
00026 int32 TIMED_OUT=-2
00027
00028 # start state errors
00029 int32 START_STATE_IN_COLLISION=-3
00030 int32 START_STATE_VIOLATES_PATH_CONSTRAINTS=-4
00031
00032 # goal errors
00033 int32 GOAL_IN_COLLISION=-5
00034 int32 GOAL_VIOLATES_PATH_CONSTRAINTS=-6
00035
00036 # robot state
00037 int32 INVALID_ROBOT_STATE=-7
00038 int32 INCOMPLETE_ROBOT_STATE=-8
00039
00040 # planning request errors
00041 int32 INVALID_PLANNER_ID=-9
00042 int32 INVALID_NUM_PLANNING_ATTEMPTS=-10
00043 int32 INVALID_ALLOWED_PLANNING_TIME=-11
00044 int32 INVALID_GROUP_NAME=-12
00045 int32 INVALID_GOAL_JOINT_CONSTRAINTS=-13
00046 int32 INVALID_GOAL_POSITION_CONSTRAINTS=-14
00047 int32 INVALID_GOAL_ORIENTATION_CONSTRAINTS=-15
00048 int32 INVALID_PATH_JOINT_CONSTRAINTS=-16
00049 int32 INVALID_PATH_POSITION_CONSTRAINTS=-17
00050 int32 INVALID_PATH_ORIENTATION_CONSTRAINTS=-18
00051
00052 # state/trajectory monitor errors
00053 int32 INVALID_TRAJECTORY=-19
00054 int32 INVALID_INDEX=-20
00055 int32 JOINT_LIMITS_VIOLATED=-21
00056 int32 PATH_CONSTRAINTS_VIOLATED=-22
00057 int32 COLLISION_CONSTRAINTS_VIOLATED=-23
00058 int32 GOAL_CONSTRAINTS_VIOLATED=-24
00059 int32 JOINTS_NOT_MOVING=-25
00060 int32 TRAJECTORY_CONTROLLER_FAILED=-26
00061
00062 # system errors
00063 int32 FRAME_TRANSFORM_FAILURE=-27
00064 int32 COLLISION_CHECKING_UNAVAILABLE=-28
00065 int32 ROBOT_STATE_STALE=-29
00066 int32 SENSOR_INFO_STALE=-30
00067
00068 # kinematics errors
00069 int32 NO_IK_SOLUTION=-31
00070 int32 INVALID_LINK_NAME=-32
00071 int32 IK_LINK_IN_COLLISION=-33
00072 int32 NO_FK_SOLUTION=-34
00073 int32 KINEMATICS_STATE_IN_COLLISION=-35
00074
00075 # general errors
00076 int32 INVALID_TIMEOUT=-36
00077
00078
00079 ================================================================================
00080 MSG: arm_navigation_msgs/ContactInformation
00081 # Standard ROS header contains information
00082 # about the frame in which this
00083 # contact is specified
00084 Header header
00085
00086 # Position of the contact point
00087 geometry_msgs/Point position
00088
00089 # Normal corresponding to the contact point
00090 geometry_msgs/Vector3 normal
00091
00092 # Depth of contact point
00093 float64 depth
00094
00095 # Name of the first body that is in contact
00096 # This could be a link or a namespace that represents a body
00097 string contact_body_1
00098 string attached_body_1
00099 uint32 body_type_1
00100
00101 # Name of the second body that is in contact
00102 # This could be a link or a namespace that represents a body
00103 string contact_body_2
00104 string attached_body_2
00105 uint32 body_type_2
00106
00107 uint32 ROBOT_LINK=0
00108 uint32 OBJECT=1
00109 uint32 ATTACHED_BODY=2
00110 ================================================================================
00111 MSG: std_msgs/Header
00112 # Standard metadata for higher-level stamped data types.
00113 # This is generally used to communicate timestamped data
00114 # in a particular coordinate frame.
00115 #
00116 # sequence ID: consecutively increasing ID
00117 uint32 seq
00118 #Two-integer timestamp that is expressed as:
00119 # * stamp.secs: seconds (stamp_secs) since epoch
00120 # * stamp.nsecs: nanoseconds since stamp_secs
00121 # time-handling sugar is provided by the client library
00122 time stamp
00123 #Frame this data is associated with
00124 # 0: no frame
00125 # 1: global frame
00126 string frame_id
00127
00128 ================================================================================
00129 MSG: geometry_msgs/Point
00130 # This contains the position of a point in free space
00131 float64 x
00132 float64 y
00133 float64 z
00134
00135 ================================================================================
00136 MSG: geometry_msgs/Vector3
00137 # This represents a vector in free space.
00138
00139 float64 x
00140 float64 y
00141 float64 z
00142 """
00143 __slots__ = ['error_code','contacts']
00144 _slot_types = ['arm_navigation_msgs/ArmNavigationErrorCodes','arm_navigation_msgs/ContactInformation[]']
00145
00146 def __init__(self, *args, **kwds):
00147 """
00148 Constructor. Any message fields that are implicitly/explicitly
00149 set to None will be assigned a default value. The recommend
00150 use is keyword arguments as this is more robust to future message
00151 changes. You cannot mix in-order arguments and keyword arguments.
00152
00153 The available fields are:
00154 error_code,contacts
00155
00156 @param args: complete set of field values, in .msg order
00157 @param kwds: use keyword arguments corresponding to message field names
00158 to set specific fields.
00159 """
00160 if args or kwds:
00161 super(MoveArmResult, self).__init__(*args, **kwds)
00162
00163 if self.error_code is None:
00164 self.error_code = arm_navigation_msgs.msg.ArmNavigationErrorCodes()
00165 if self.contacts is None:
00166 self.contacts = []
00167 else:
00168 self.error_code = arm_navigation_msgs.msg.ArmNavigationErrorCodes()
00169 self.contacts = []
00170
00171 def _get_types(self):
00172 """
00173 internal API method
00174 """
00175 return self._slot_types
00176
00177 def serialize(self, buff):
00178 """
00179 serialize message into buffer
00180 @param buff: buffer
00181 @type buff: StringIO
00182 """
00183 try:
00184 buff.write(_struct_i.pack(self.error_code.val))
00185 length = len(self.contacts)
00186 buff.write(_struct_I.pack(length))
00187 for val1 in self.contacts:
00188 _v1 = val1.header
00189 buff.write(_struct_I.pack(_v1.seq))
00190 _v2 = _v1.stamp
00191 _x = _v2
00192 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00193 _x = _v1.frame_id
00194 length = len(_x)
00195 buff.write(struct.pack('<I%ss'%length, length, _x))
00196 _v3 = val1.position
00197 _x = _v3
00198 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00199 _v4 = val1.normal
00200 _x = _v4
00201 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00202 buff.write(_struct_d.pack(val1.depth))
00203 _x = val1.contact_body_1
00204 length = len(_x)
00205 buff.write(struct.pack('<I%ss'%length, length, _x))
00206 _x = val1.attached_body_1
00207 length = len(_x)
00208 buff.write(struct.pack('<I%ss'%length, length, _x))
00209 buff.write(_struct_I.pack(val1.body_type_1))
00210 _x = val1.contact_body_2
00211 length = len(_x)
00212 buff.write(struct.pack('<I%ss'%length, length, _x))
00213 _x = val1.attached_body_2
00214 length = len(_x)
00215 buff.write(struct.pack('<I%ss'%length, length, _x))
00216 buff.write(_struct_I.pack(val1.body_type_2))
00217 except struct.error as se: self._check_types(se)
00218 except TypeError as te: self._check_types(te)
00219
00220 def deserialize(self, str):
00221 """
00222 unpack serialized message in str into this message instance
00223 @param str: byte array of serialized message
00224 @type str: str
00225 """
00226 try:
00227 if self.error_code is None:
00228 self.error_code = arm_navigation_msgs.msg.ArmNavigationErrorCodes()
00229 end = 0
00230 start = end
00231 end += 4
00232 (self.error_code.val,) = _struct_i.unpack(str[start:end])
00233 start = end
00234 end += 4
00235 (length,) = _struct_I.unpack(str[start:end])
00236 self.contacts = []
00237 for i in range(0, length):
00238 val1 = arm_navigation_msgs.msg.ContactInformation()
00239 _v5 = val1.header
00240 start = end
00241 end += 4
00242 (_v5.seq,) = _struct_I.unpack(str[start:end])
00243 _v6 = _v5.stamp
00244 _x = _v6
00245 start = end
00246 end += 8
00247 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00248 start = end
00249 end += 4
00250 (length,) = _struct_I.unpack(str[start:end])
00251 start = end
00252 end += length
00253 _v5.frame_id = str[start:end]
00254 _v7 = val1.position
00255 _x = _v7
00256 start = end
00257 end += 24
00258 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00259 _v8 = val1.normal
00260 _x = _v8
00261 start = end
00262 end += 24
00263 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00264 start = end
00265 end += 8
00266 (val1.depth,) = _struct_d.unpack(str[start:end])
00267 start = end
00268 end += 4
00269 (length,) = _struct_I.unpack(str[start:end])
00270 start = end
00271 end += length
00272 val1.contact_body_1 = str[start:end]
00273 start = end
00274 end += 4
00275 (length,) = _struct_I.unpack(str[start:end])
00276 start = end
00277 end += length
00278 val1.attached_body_1 = str[start:end]
00279 start = end
00280 end += 4
00281 (val1.body_type_1,) = _struct_I.unpack(str[start:end])
00282 start = end
00283 end += 4
00284 (length,) = _struct_I.unpack(str[start:end])
00285 start = end
00286 end += length
00287 val1.contact_body_2 = str[start:end]
00288 start = end
00289 end += 4
00290 (length,) = _struct_I.unpack(str[start:end])
00291 start = end
00292 end += length
00293 val1.attached_body_2 = str[start:end]
00294 start = end
00295 end += 4
00296 (val1.body_type_2,) = _struct_I.unpack(str[start:end])
00297 self.contacts.append(val1)
00298 return self
00299 except struct.error as e:
00300 raise roslib.message.DeserializationError(e)
00301
00302
00303 def serialize_numpy(self, buff, numpy):
00304 """
00305 serialize message with numpy array types into buffer
00306 @param buff: buffer
00307 @type buff: StringIO
00308 @param numpy: numpy python module
00309 @type numpy module
00310 """
00311 try:
00312 buff.write(_struct_i.pack(self.error_code.val))
00313 length = len(self.contacts)
00314 buff.write(_struct_I.pack(length))
00315 for val1 in self.contacts:
00316 _v9 = val1.header
00317 buff.write(_struct_I.pack(_v9.seq))
00318 _v10 = _v9.stamp
00319 _x = _v10
00320 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00321 _x = _v9.frame_id
00322 length = len(_x)
00323 buff.write(struct.pack('<I%ss'%length, length, _x))
00324 _v11 = val1.position
00325 _x = _v11
00326 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00327 _v12 = val1.normal
00328 _x = _v12
00329 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00330 buff.write(_struct_d.pack(val1.depth))
00331 _x = val1.contact_body_1
00332 length = len(_x)
00333 buff.write(struct.pack('<I%ss'%length, length, _x))
00334 _x = val1.attached_body_1
00335 length = len(_x)
00336 buff.write(struct.pack('<I%ss'%length, length, _x))
00337 buff.write(_struct_I.pack(val1.body_type_1))
00338 _x = val1.contact_body_2
00339 length = len(_x)
00340 buff.write(struct.pack('<I%ss'%length, length, _x))
00341 _x = val1.attached_body_2
00342 length = len(_x)
00343 buff.write(struct.pack('<I%ss'%length, length, _x))
00344 buff.write(_struct_I.pack(val1.body_type_2))
00345 except struct.error as se: self._check_types(se)
00346 except TypeError as te: self._check_types(te)
00347
00348 def deserialize_numpy(self, str, numpy):
00349 """
00350 unpack serialized message in str into this message instance using numpy for array types
00351 @param str: byte array of serialized message
00352 @type str: str
00353 @param numpy: numpy python module
00354 @type numpy: module
00355 """
00356 try:
00357 if self.error_code is None:
00358 self.error_code = arm_navigation_msgs.msg.ArmNavigationErrorCodes()
00359 end = 0
00360 start = end
00361 end += 4
00362 (self.error_code.val,) = _struct_i.unpack(str[start:end])
00363 start = end
00364 end += 4
00365 (length,) = _struct_I.unpack(str[start:end])
00366 self.contacts = []
00367 for i in range(0, length):
00368 val1 = arm_navigation_msgs.msg.ContactInformation()
00369 _v13 = val1.header
00370 start = end
00371 end += 4
00372 (_v13.seq,) = _struct_I.unpack(str[start:end])
00373 _v14 = _v13.stamp
00374 _x = _v14
00375 start = end
00376 end += 8
00377 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00378 start = end
00379 end += 4
00380 (length,) = _struct_I.unpack(str[start:end])
00381 start = end
00382 end += length
00383 _v13.frame_id = str[start:end]
00384 _v15 = val1.position
00385 _x = _v15
00386 start = end
00387 end += 24
00388 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00389 _v16 = val1.normal
00390 _x = _v16
00391 start = end
00392 end += 24
00393 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00394 start = end
00395 end += 8
00396 (val1.depth,) = _struct_d.unpack(str[start:end])
00397 start = end
00398 end += 4
00399 (length,) = _struct_I.unpack(str[start:end])
00400 start = end
00401 end += length
00402 val1.contact_body_1 = str[start:end]
00403 start = end
00404 end += 4
00405 (length,) = _struct_I.unpack(str[start:end])
00406 start = end
00407 end += length
00408 val1.attached_body_1 = str[start:end]
00409 start = end
00410 end += 4
00411 (val1.body_type_1,) = _struct_I.unpack(str[start:end])
00412 start = end
00413 end += 4
00414 (length,) = _struct_I.unpack(str[start:end])
00415 start = end
00416 end += length
00417 val1.contact_body_2 = str[start:end]
00418 start = end
00419 end += 4
00420 (length,) = _struct_I.unpack(str[start:end])
00421 start = end
00422 end += length
00423 val1.attached_body_2 = str[start:end]
00424 start = end
00425 end += 4
00426 (val1.body_type_2,) = _struct_I.unpack(str[start:end])
00427 self.contacts.append(val1)
00428 return self
00429 except struct.error as e:
00430 raise roslib.message.DeserializationError(e)
00431
00432 _struct_I = roslib.message.struct_I
00433 _struct_i = struct.Struct("<i")
00434 _struct_2I = struct.Struct("<2I")
00435 _struct_d = struct.Struct("<d")
00436 _struct_3d = struct.Struct("<3d")