00001 """autogenerated by genmsg_py from ConstraintGraphMessage.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import geometry_msgs.msg
00006 import graph_mapping_msgs.msg
00007
00008 class ConstraintGraphMessage(roslib.message.Message):
00009 _md5sum = "cda8ffff59a7c01fc6f86d350d17f4c7"
00010 _type = "graph_mapping_msgs/ConstraintGraphMessage"
00011 _has_header = False
00012 _full_text = """Node[] nodes
00013 Edge[] edges
00014 ================================================================================
00015 MSG: graph_mapping_msgs/Node
00016 uint32 id
00017
00018 # This array has length 1 if the node has an optimized pose; 0 otherwise
00019 geometry_msgs/Pose[] optimized_pose
00020
00021
00022 ================================================================================
00023 MSG: geometry_msgs/Pose
00024 # A representation of pose in free space, composed of postion and orientation.
00025 Point position
00026 Quaternion orientation
00027
00028 ================================================================================
00029 MSG: geometry_msgs/Point
00030 # This contains the position of a point in free space
00031 float64 x
00032 float64 y
00033 float64 z
00034
00035 ================================================================================
00036 MSG: geometry_msgs/Quaternion
00037 # This represents an orientation in free space in quaternion form.
00038
00039 float64 x
00040 float64 y
00041 float64 z
00042 float64 w
00043
00044 ================================================================================
00045 MSG: graph_mapping_msgs/Edge
00046 uint32 id
00047 GraphConstraint constraint
00048
00049 ================================================================================
00050 MSG: graph_mapping_msgs/GraphConstraint
00051 uint32 src
00052 uint32 dest
00053 PoseWithPrecision constraint
00054 ================================================================================
00055 MSG: graph_mapping_msgs/PoseWithPrecision
00056 geometry_msgs/Pose pose
00057 float64[36] precision
00058 """
00059 __slots__ = ['nodes','edges']
00060 _slot_types = ['graph_mapping_msgs/Node[]','graph_mapping_msgs/Edge[]']
00061
00062 def __init__(self, *args, **kwds):
00063 """
00064 Constructor. Any message fields that are implicitly/explicitly
00065 set to None will be assigned a default value. The recommend
00066 use is keyword arguments as this is more robust to future message
00067 changes. You cannot mix in-order arguments and keyword arguments.
00068
00069 The available fields are:
00070 nodes,edges
00071
00072 @param args: complete set of field values, in .msg order
00073 @param kwds: use keyword arguments corresponding to message field names
00074 to set specific fields.
00075 """
00076 if args or kwds:
00077 super(ConstraintGraphMessage, self).__init__(*args, **kwds)
00078
00079 if self.nodes is None:
00080 self.nodes = []
00081 if self.edges is None:
00082 self.edges = []
00083 else:
00084 self.nodes = []
00085 self.edges = []
00086
00087 def _get_types(self):
00088 """
00089 internal API method
00090 """
00091 return self._slot_types
00092
00093 def serialize(self, buff):
00094 """
00095 serialize message into buffer
00096 @param buff: buffer
00097 @type buff: StringIO
00098 """
00099 try:
00100 length = len(self.nodes)
00101 buff.write(_struct_I.pack(length))
00102 for val1 in self.nodes:
00103 buff.write(_struct_I.pack(val1.id))
00104 length = len(val1.optimized_pose)
00105 buff.write(_struct_I.pack(length))
00106 for val2 in val1.optimized_pose:
00107 _v1 = val2.position
00108 _x = _v1
00109 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00110 _v2 = val2.orientation
00111 _x = _v2
00112 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00113 length = len(self.edges)
00114 buff.write(_struct_I.pack(length))
00115 for val1 in self.edges:
00116 buff.write(_struct_I.pack(val1.id))
00117 _v3 = val1.constraint
00118 _x = _v3
00119 buff.write(_struct_2I.pack(_x.src, _x.dest))
00120 _v4 = _v3.constraint
00121 _v5 = _v4.pose
00122 _v6 = _v5.position
00123 _x = _v6
00124 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00125 _v7 = _v5.orientation
00126 _x = _v7
00127 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00128 buff.write(_struct_36d.pack(*_v4.precision))
00129 except struct.error, se: self._check_types(se)
00130 except TypeError, te: self._check_types(te)
00131
00132 def deserialize(self, str):
00133 """
00134 unpack serialized message in str into this message instance
00135 @param str: byte array of serialized message
00136 @type str: str
00137 """
00138 try:
00139 end = 0
00140 start = end
00141 end += 4
00142 (length,) = _struct_I.unpack(str[start:end])
00143 self.nodes = []
00144 for i in xrange(0, length):
00145 val1 = graph_mapping_msgs.msg.Node()
00146 start = end
00147 end += 4
00148 (val1.id,) = _struct_I.unpack(str[start:end])
00149 start = end
00150 end += 4
00151 (length,) = _struct_I.unpack(str[start:end])
00152 val1.optimized_pose = []
00153 for i in xrange(0, length):
00154 val2 = geometry_msgs.msg.Pose()
00155 _v8 = val2.position
00156 _x = _v8
00157 start = end
00158 end += 24
00159 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00160 _v9 = val2.orientation
00161 _x = _v9
00162 start = end
00163 end += 32
00164 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00165 val1.optimized_pose.append(val2)
00166 self.nodes.append(val1)
00167 start = end
00168 end += 4
00169 (length,) = _struct_I.unpack(str[start:end])
00170 self.edges = []
00171 for i in xrange(0, length):
00172 val1 = graph_mapping_msgs.msg.Edge()
00173 start = end
00174 end += 4
00175 (val1.id,) = _struct_I.unpack(str[start:end])
00176 _v10 = val1.constraint
00177 _x = _v10
00178 start = end
00179 end += 8
00180 (_x.src, _x.dest,) = _struct_2I.unpack(str[start:end])
00181 _v11 = _v10.constraint
00182 _v12 = _v11.pose
00183 _v13 = _v12.position
00184 _x = _v13
00185 start = end
00186 end += 24
00187 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00188 _v14 = _v12.orientation
00189 _x = _v14
00190 start = end
00191 end += 32
00192 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00193 start = end
00194 end += 288
00195 _v11.precision = _struct_36d.unpack(str[start:end])
00196 self.edges.append(val1)
00197 return self
00198 except struct.error, e:
00199 raise roslib.message.DeserializationError(e)
00200
00201
00202 def serialize_numpy(self, buff, numpy):
00203 """
00204 serialize message with numpy array types into buffer
00205 @param buff: buffer
00206 @type buff: StringIO
00207 @param numpy: numpy python module
00208 @type numpy module
00209 """
00210 try:
00211 length = len(self.nodes)
00212 buff.write(_struct_I.pack(length))
00213 for val1 in self.nodes:
00214 buff.write(_struct_I.pack(val1.id))
00215 length = len(val1.optimized_pose)
00216 buff.write(_struct_I.pack(length))
00217 for val2 in val1.optimized_pose:
00218 _v15 = val2.position
00219 _x = _v15
00220 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00221 _v16 = val2.orientation
00222 _x = _v16
00223 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00224 length = len(self.edges)
00225 buff.write(_struct_I.pack(length))
00226 for val1 in self.edges:
00227 buff.write(_struct_I.pack(val1.id))
00228 _v17 = val1.constraint
00229 _x = _v17
00230 buff.write(_struct_2I.pack(_x.src, _x.dest))
00231 _v18 = _v17.constraint
00232 _v19 = _v18.pose
00233 _v20 = _v19.position
00234 _x = _v20
00235 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00236 _v21 = _v19.orientation
00237 _x = _v21
00238 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00239 buff.write(_v18.precision.tostring())
00240 except struct.error, se: self._check_types(se)
00241 except TypeError, te: self._check_types(te)
00242
00243 def deserialize_numpy(self, str, numpy):
00244 """
00245 unpack serialized message in str into this message instance using numpy for array types
00246 @param str: byte array of serialized message
00247 @type str: str
00248 @param numpy: numpy python module
00249 @type numpy: module
00250 """
00251 try:
00252 end = 0
00253 start = end
00254 end += 4
00255 (length,) = _struct_I.unpack(str[start:end])
00256 self.nodes = []
00257 for i in xrange(0, length):
00258 val1 = graph_mapping_msgs.msg.Node()
00259 start = end
00260 end += 4
00261 (val1.id,) = _struct_I.unpack(str[start:end])
00262 start = end
00263 end += 4
00264 (length,) = _struct_I.unpack(str[start:end])
00265 val1.optimized_pose = []
00266 for i in xrange(0, length):
00267 val2 = geometry_msgs.msg.Pose()
00268 _v22 = val2.position
00269 _x = _v22
00270 start = end
00271 end += 24
00272 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00273 _v23 = val2.orientation
00274 _x = _v23
00275 start = end
00276 end += 32
00277 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00278 val1.optimized_pose.append(val2)
00279 self.nodes.append(val1)
00280 start = end
00281 end += 4
00282 (length,) = _struct_I.unpack(str[start:end])
00283 self.edges = []
00284 for i in xrange(0, length):
00285 val1 = graph_mapping_msgs.msg.Edge()
00286 start = end
00287 end += 4
00288 (val1.id,) = _struct_I.unpack(str[start:end])
00289 _v24 = val1.constraint
00290 _x = _v24
00291 start = end
00292 end += 8
00293 (_x.src, _x.dest,) = _struct_2I.unpack(str[start:end])
00294 _v25 = _v24.constraint
00295 _v26 = _v25.pose
00296 _v27 = _v26.position
00297 _x = _v27
00298 start = end
00299 end += 24
00300 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00301 _v28 = _v26.orientation
00302 _x = _v28
00303 start = end
00304 end += 32
00305 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00306 start = end
00307 end += 288
00308 _v25.precision = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=36)
00309 self.edges.append(val1)
00310 return self
00311 except struct.error, e:
00312 raise roslib.message.DeserializationError(e)
00313
00314 _struct_I = roslib.message.struct_I
00315 _struct_36d = struct.Struct("<36d")
00316 _struct_4d = struct.Struct("<4d")
00317 _struct_2I = struct.Struct("<2I")
00318 _struct_3d = struct.Struct("<3d")