00001 """autogenerated by genmsg_py from TopologicalRoadmap.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import geometry_msgs.msg
00006 import topological_nav_msgs.msg
00007
00008 class TopologicalRoadmap(roslib.message.Message):
00009 _md5sum = "3860d4f5bd292b2fc201613203c01a2a"
00010 _type = "topological_nav_msgs/TopologicalRoadmap"
00011 _has_header = False
00012 _full_text = """# A topological roadmap consists of nodes representing navigation waypoints
00013 # and edges representing navigable connections.
00014
00015 RoadmapNode[] nodes
00016 RoadmapEdge[] edges
00017 ================================================================================
00018 MSG: topological_nav_msgs/RoadmapNode
00019 # Info stored with a waypoint node in the topological roadmap
00020
00021 # Id of this node in the roadmap
00022 uint32 id
00023
00024 # Id of the topological map grid wrt which this waypoint position is defined
00025 uint32 grid
00026
00027 # Relative position in the grid frame
00028 geometry_msgs/Point position
00029 ================================================================================
00030 MSG: geometry_msgs/Point
00031 # This contains the position of a point in free space
00032 float64 x
00033 float64 y
00034 float64 z
00035
00036 ================================================================================
00037 MSG: topological_nav_msgs/RoadmapEdge
00038 # Info stored with an edge in the roadmap
00039
00040 # Id of this edge in the roadmap.
00041 uint32 id
00042
00043 # Grid this edge lives on
00044 uint32 grid
00045
00046 # Source node of the edge; must belong to the grid.
00047 uint32 src
00048
00049 # Target node of the edge; must belong to the grid.
00050 uint32 dest
00051
00052 # Cost of this edge
00053 float32 cost
00054 """
00055 __slots__ = ['nodes','edges']
00056 _slot_types = ['topological_nav_msgs/RoadmapNode[]','topological_nav_msgs/RoadmapEdge[]']
00057
00058 def __init__(self, *args, **kwds):
00059 """
00060 Constructor. Any message fields that are implicitly/explicitly
00061 set to None will be assigned a default value. The recommend
00062 use is keyword arguments as this is more robust to future message
00063 changes. You cannot mix in-order arguments and keyword arguments.
00064
00065 The available fields are:
00066 nodes,edges
00067
00068 @param args: complete set of field values, in .msg order
00069 @param kwds: use keyword arguments corresponding to message field names
00070 to set specific fields.
00071 """
00072 if args or kwds:
00073 super(TopologicalRoadmap, self).__init__(*args, **kwds)
00074
00075 if self.nodes is None:
00076 self.nodes = []
00077 if self.edges is None:
00078 self.edges = []
00079 else:
00080 self.nodes = []
00081 self.edges = []
00082
00083 def _get_types(self):
00084 """
00085 internal API method
00086 """
00087 return self._slot_types
00088
00089 def serialize(self, buff):
00090 """
00091 serialize message into buffer
00092 @param buff: buffer
00093 @type buff: StringIO
00094 """
00095 try:
00096 length = len(self.nodes)
00097 buff.write(_struct_I.pack(length))
00098 for val1 in self.nodes:
00099 _x = val1
00100 buff.write(_struct_2I.pack(_x.id, _x.grid))
00101 _v1 = val1.position
00102 _x = _v1
00103 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00104 length = len(self.edges)
00105 buff.write(_struct_I.pack(length))
00106 for val1 in self.edges:
00107 _x = val1
00108 buff.write(_struct_4If.pack(_x.id, _x.grid, _x.src, _x.dest, _x.cost))
00109 except struct.error, se: self._check_types(se)
00110 except TypeError, te: self._check_types(te)
00111
00112 def deserialize(self, str):
00113 """
00114 unpack serialized message in str into this message instance
00115 @param str: byte array of serialized message
00116 @type str: str
00117 """
00118 try:
00119 end = 0
00120 start = end
00121 end += 4
00122 (length,) = _struct_I.unpack(str[start:end])
00123 self.nodes = []
00124 for i in xrange(0, length):
00125 val1 = topological_nav_msgs.msg.RoadmapNode()
00126 _x = val1
00127 start = end
00128 end += 8
00129 (_x.id, _x.grid,) = _struct_2I.unpack(str[start:end])
00130 _v2 = val1.position
00131 _x = _v2
00132 start = end
00133 end += 24
00134 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00135 self.nodes.append(val1)
00136 start = end
00137 end += 4
00138 (length,) = _struct_I.unpack(str[start:end])
00139 self.edges = []
00140 for i in xrange(0, length):
00141 val1 = topological_nav_msgs.msg.RoadmapEdge()
00142 _x = val1
00143 start = end
00144 end += 20
00145 (_x.id, _x.grid, _x.src, _x.dest, _x.cost,) = _struct_4If.unpack(str[start:end])
00146 self.edges.append(val1)
00147 return self
00148 except struct.error, e:
00149 raise roslib.message.DeserializationError(e)
00150
00151
00152 def serialize_numpy(self, buff, numpy):
00153 """
00154 serialize message with numpy array types into buffer
00155 @param buff: buffer
00156 @type buff: StringIO
00157 @param numpy: numpy python module
00158 @type numpy module
00159 """
00160 try:
00161 length = len(self.nodes)
00162 buff.write(_struct_I.pack(length))
00163 for val1 in self.nodes:
00164 _x = val1
00165 buff.write(_struct_2I.pack(_x.id, _x.grid))
00166 _v3 = val1.position
00167 _x = _v3
00168 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00169 length = len(self.edges)
00170 buff.write(_struct_I.pack(length))
00171 for val1 in self.edges:
00172 _x = val1
00173 buff.write(_struct_4If.pack(_x.id, _x.grid, _x.src, _x.dest, _x.cost))
00174 except struct.error, se: self._check_types(se)
00175 except TypeError, te: self._check_types(te)
00176
00177 def deserialize_numpy(self, str, numpy):
00178 """
00179 unpack serialized message in str into this message instance using numpy for array types
00180 @param str: byte array of serialized message
00181 @type str: str
00182 @param numpy: numpy python module
00183 @type numpy: module
00184 """
00185 try:
00186 end = 0
00187 start = end
00188 end += 4
00189 (length,) = _struct_I.unpack(str[start:end])
00190 self.nodes = []
00191 for i in xrange(0, length):
00192 val1 = topological_nav_msgs.msg.RoadmapNode()
00193 _x = val1
00194 start = end
00195 end += 8
00196 (_x.id, _x.grid,) = _struct_2I.unpack(str[start:end])
00197 _v4 = val1.position
00198 _x = _v4
00199 start = end
00200 end += 24
00201 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00202 self.nodes.append(val1)
00203 start = end
00204 end += 4
00205 (length,) = _struct_I.unpack(str[start:end])
00206 self.edges = []
00207 for i in xrange(0, length):
00208 val1 = topological_nav_msgs.msg.RoadmapEdge()
00209 _x = val1
00210 start = end
00211 end += 20
00212 (_x.id, _x.grid, _x.src, _x.dest, _x.cost,) = _struct_4If.unpack(str[start:end])
00213 self.edges.append(val1)
00214 return self
00215 except struct.error, e:
00216 raise roslib.message.DeserializationError(e)
00217
00218 _struct_I = roslib.message.struct_I
00219 _struct_4If = struct.Struct("<4If")
00220 _struct_2I = struct.Struct("<2I")
00221 _struct_3d = struct.Struct("<3d")