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