00001
00002 #ifndef TOPOLOGICAL_NAV_MSGS_MESSAGE_TOPOLOGICALGRAPH_H
00003 #define TOPOLOGICAL_NAV_MSGS_MESSAGE_TOPOLOGICALGRAPH_H
00004 #include <string>
00005 #include <vector>
00006 #include <ostream>
00007 #include "ros/serialization.h"
00008 #include "ros/builtin_message_traits.h"
00009 #include "ros/message_operations.h"
00010 #include "ros/message.h"
00011 #include "ros/time.h"
00012
00013 #include "topological_nav_msgs/TopologicalMapNode.h"
00014 #include "topological_nav_msgs/TopologicalMapEdge.h"
00015
00016 namespace topological_nav_msgs
00017 {
00018 template <class ContainerAllocator>
00019 struct TopologicalGraph_ : public ros::Message
00020 {
00021 typedef TopologicalGraph_<ContainerAllocator> Type;
00022
00023 TopologicalGraph_()
00024 : nodes()
00025 , edges()
00026 {
00027 }
00028
00029 TopologicalGraph_(const ContainerAllocator& _alloc)
00030 : nodes(_alloc)
00031 , edges(_alloc)
00032 {
00033 }
00034
00035 typedef std::vector< ::topological_nav_msgs::TopologicalMapNode_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::topological_nav_msgs::TopologicalMapNode_<ContainerAllocator> >::other > _nodes_type;
00036 std::vector< ::topological_nav_msgs::TopologicalMapNode_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::topological_nav_msgs::TopologicalMapNode_<ContainerAllocator> >::other > nodes;
00037
00038 typedef std::vector< ::topological_nav_msgs::TopologicalMapEdge_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::topological_nav_msgs::TopologicalMapEdge_<ContainerAllocator> >::other > _edges_type;
00039 std::vector< ::topological_nav_msgs::TopologicalMapEdge_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::topological_nav_msgs::TopologicalMapEdge_<ContainerAllocator> >::other > edges;
00040
00041
00042 ROS_DEPRECATED uint32_t get_nodes_size() const { return (uint32_t)nodes.size(); }
00043 ROS_DEPRECATED void set_nodes_size(uint32_t size) { nodes.resize((size_t)size); }
00044 ROS_DEPRECATED void get_nodes_vec(std::vector< ::topological_nav_msgs::TopologicalMapNode_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::topological_nav_msgs::TopologicalMapNode_<ContainerAllocator> >::other > & vec) const { vec = this->nodes; }
00045 ROS_DEPRECATED void set_nodes_vec(const std::vector< ::topological_nav_msgs::TopologicalMapNode_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::topological_nav_msgs::TopologicalMapNode_<ContainerAllocator> >::other > & vec) { this->nodes = vec; }
00046 ROS_DEPRECATED uint32_t get_edges_size() const { return (uint32_t)edges.size(); }
00047 ROS_DEPRECATED void set_edges_size(uint32_t size) { edges.resize((size_t)size); }
00048 ROS_DEPRECATED void get_edges_vec(std::vector< ::topological_nav_msgs::TopologicalMapEdge_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::topological_nav_msgs::TopologicalMapEdge_<ContainerAllocator> >::other > & vec) const { vec = this->edges; }
00049 ROS_DEPRECATED void set_edges_vec(const std::vector< ::topological_nav_msgs::TopologicalMapEdge_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::topological_nav_msgs::TopologicalMapEdge_<ContainerAllocator> >::other > & vec) { this->edges = vec; }
00050 private:
00051 static const char* __s_getDataType_() { return "topological_nav_msgs/TopologicalGraph"; }
00052 public:
00053 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00054
00055 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00056
00057 private:
00058 static const char* __s_getMD5Sum_() { return "a0ab3936a4c52a67e3590fae99c61eb4"; }
00059 public:
00060 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00061
00062 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00063
00064 private:
00065 static const char* __s_getMessageDefinition_() { return "# A 2d topological map consists of a set of local occupancy grids together with\n\
00066 # the transformations between coordinate frames of overlapping grids. This ROS\n\
00067 # message represents the structure of the topological map, i.e., all the \n\
00068 # information except the grids themselves. You can get individual grids by\n\
00069 # calling the GetLocalGrid service on the mapper.\n\
00070 \n\
00071 TopologicalMapNode[] nodes\n\
00072 TopologicalMapEdge[] edges\n\
00073 ================================================================================\n\
00074 MSG: topological_nav_msgs/TopologicalMapNode\n\
00075 # Info stored with a node in a 2d topological map\n\
00076 \n\
00077 # Id of this node in the topological map\n\
00078 uint32 id\n\
00079 \n\
00080 # Dimensions of local grid. The local grid covers the rectangle between\n\
00081 # (0,0) and (x_size, y_size) in the grid's frame\n\
00082 float32 x_size\n\
00083 float32 y_size\n\
00084 \n\
00085 # Resolution of the local occupancy grid\n\
00086 float32 resolution\n\
00087 \n\
00088 \n\
00089 ================================================================================\n\
00090 MSG: topological_nav_msgs/TopologicalMapEdge\n\
00091 # Info stored with an edge in 2d topological map\n\
00092 \n\
00093 # Id of this edge in the topological map\n\
00094 uint32 id\n\
00095 \n\
00096 # Id of the source node\n\
00097 uint32 src\n\
00098 \n\
00099 # Id of the destination node\n\
00100 uint32 dest\n\
00101 \n\
00102 # Pose of origin of destination node's coordinate frame\n\
00103 # represented in the source node's coordinate frame\n\
00104 geometry_msgs/Pose offset\n\
00105 \n\
00106 ================================================================================\n\
00107 MSG: geometry_msgs/Pose\n\
00108 # A representation of pose in free space, composed of postion and orientation. \n\
00109 Point position\n\
00110 Quaternion orientation\n\
00111 \n\
00112 ================================================================================\n\
00113 MSG: geometry_msgs/Point\n\
00114 # This contains the position of a point in free space\n\
00115 float64 x\n\
00116 float64 y\n\
00117 float64 z\n\
00118 \n\
00119 ================================================================================\n\
00120 MSG: geometry_msgs/Quaternion\n\
00121 # This represents an orientation in free space in quaternion form.\n\
00122 \n\
00123 float64 x\n\
00124 float64 y\n\
00125 float64 z\n\
00126 float64 w\n\
00127 \n\
00128 "; }
00129 public:
00130 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00131
00132 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00133
00134 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00135 {
00136 ros::serialization::OStream stream(write_ptr, 1000000000);
00137 ros::serialization::serialize(stream, nodes);
00138 ros::serialization::serialize(stream, edges);
00139 return stream.getData();
00140 }
00141
00142 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00143 {
00144 ros::serialization::IStream stream(read_ptr, 1000000000);
00145 ros::serialization::deserialize(stream, nodes);
00146 ros::serialization::deserialize(stream, edges);
00147 return stream.getData();
00148 }
00149
00150 ROS_DEPRECATED virtual uint32_t serializationLength() const
00151 {
00152 uint32_t size = 0;
00153 size += ros::serialization::serializationLength(nodes);
00154 size += ros::serialization::serializationLength(edges);
00155 return size;
00156 }
00157
00158 typedef boost::shared_ptr< ::topological_nav_msgs::TopologicalGraph_<ContainerAllocator> > Ptr;
00159 typedef boost::shared_ptr< ::topological_nav_msgs::TopologicalGraph_<ContainerAllocator> const> ConstPtr;
00160 };
00161 typedef ::topological_nav_msgs::TopologicalGraph_<std::allocator<void> > TopologicalGraph;
00162
00163 typedef boost::shared_ptr< ::topological_nav_msgs::TopologicalGraph> TopologicalGraphPtr;
00164 typedef boost::shared_ptr< ::topological_nav_msgs::TopologicalGraph const> TopologicalGraphConstPtr;
00165
00166
00167 template<typename ContainerAllocator>
00168 std::ostream& operator<<(std::ostream& s, const ::topological_nav_msgs::TopologicalGraph_<ContainerAllocator> & v)
00169 {
00170 ros::message_operations::Printer< ::topological_nav_msgs::TopologicalGraph_<ContainerAllocator> >::stream(s, "", v);
00171 return s;}
00172
00173 }
00174
00175 namespace ros
00176 {
00177 namespace message_traits
00178 {
00179 template<class ContainerAllocator>
00180 struct MD5Sum< ::topological_nav_msgs::TopologicalGraph_<ContainerAllocator> > {
00181 static const char* value()
00182 {
00183 return "a0ab3936a4c52a67e3590fae99c61eb4";
00184 }
00185
00186 static const char* value(const ::topological_nav_msgs::TopologicalGraph_<ContainerAllocator> &) { return value(); }
00187 static const uint64_t static_value1 = 0xa0ab3936a4c52a67ULL;
00188 static const uint64_t static_value2 = 0xe3590fae99c61eb4ULL;
00189 };
00190
00191 template<class ContainerAllocator>
00192 struct DataType< ::topological_nav_msgs::TopologicalGraph_<ContainerAllocator> > {
00193 static const char* value()
00194 {
00195 return "topological_nav_msgs/TopologicalGraph";
00196 }
00197
00198 static const char* value(const ::topological_nav_msgs::TopologicalGraph_<ContainerAllocator> &) { return value(); }
00199 };
00200
00201 template<class ContainerAllocator>
00202 struct Definition< ::topological_nav_msgs::TopologicalGraph_<ContainerAllocator> > {
00203 static const char* value()
00204 {
00205 return "# A 2d topological map consists of a set of local occupancy grids together with\n\
00206 # the transformations between coordinate frames of overlapping grids. This ROS\n\
00207 # message represents the structure of the topological map, i.e., all the \n\
00208 # information except the grids themselves. You can get individual grids by\n\
00209 # calling the GetLocalGrid service on the mapper.\n\
00210 \n\
00211 TopologicalMapNode[] nodes\n\
00212 TopologicalMapEdge[] edges\n\
00213 ================================================================================\n\
00214 MSG: topological_nav_msgs/TopologicalMapNode\n\
00215 # Info stored with a node in a 2d topological map\n\
00216 \n\
00217 # Id of this node in the topological map\n\
00218 uint32 id\n\
00219 \n\
00220 # Dimensions of local grid. The local grid covers the rectangle between\n\
00221 # (0,0) and (x_size, y_size) in the grid's frame\n\
00222 float32 x_size\n\
00223 float32 y_size\n\
00224 \n\
00225 # Resolution of the local occupancy grid\n\
00226 float32 resolution\n\
00227 \n\
00228 \n\
00229 ================================================================================\n\
00230 MSG: topological_nav_msgs/TopologicalMapEdge\n\
00231 # Info stored with an edge in 2d topological map\n\
00232 \n\
00233 # Id of this edge in the topological map\n\
00234 uint32 id\n\
00235 \n\
00236 # Id of the source node\n\
00237 uint32 src\n\
00238 \n\
00239 # Id of the destination node\n\
00240 uint32 dest\n\
00241 \n\
00242 # Pose of origin of destination node's coordinate frame\n\
00243 # represented in the source node's coordinate frame\n\
00244 geometry_msgs/Pose offset\n\
00245 \n\
00246 ================================================================================\n\
00247 MSG: geometry_msgs/Pose\n\
00248 # A representation of pose in free space, composed of postion and orientation. \n\
00249 Point position\n\
00250 Quaternion orientation\n\
00251 \n\
00252 ================================================================================\n\
00253 MSG: geometry_msgs/Point\n\
00254 # This contains the position of a point in free space\n\
00255 float64 x\n\
00256 float64 y\n\
00257 float64 z\n\
00258 \n\
00259 ================================================================================\n\
00260 MSG: geometry_msgs/Quaternion\n\
00261 # This represents an orientation in free space in quaternion form.\n\
00262 \n\
00263 float64 x\n\
00264 float64 y\n\
00265 float64 z\n\
00266 float64 w\n\
00267 \n\
00268 ";
00269 }
00270
00271 static const char* value(const ::topological_nav_msgs::TopologicalGraph_<ContainerAllocator> &) { return value(); }
00272 };
00273
00274 }
00275 }
00276
00277 namespace ros
00278 {
00279 namespace serialization
00280 {
00281
00282 template<class ContainerAllocator> struct Serializer< ::topological_nav_msgs::TopologicalGraph_<ContainerAllocator> >
00283 {
00284 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00285 {
00286 stream.next(m.nodes);
00287 stream.next(m.edges);
00288 }
00289
00290 ROS_DECLARE_ALLINONE_SERIALIZER;
00291 };
00292 }
00293 }
00294
00295 namespace ros
00296 {
00297 namespace message_operations
00298 {
00299
00300 template<class ContainerAllocator>
00301 struct Printer< ::topological_nav_msgs::TopologicalGraph_<ContainerAllocator> >
00302 {
00303 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::topological_nav_msgs::TopologicalGraph_<ContainerAllocator> & v)
00304 {
00305 s << indent << "nodes[]" << std::endl;
00306 for (size_t i = 0; i < v.nodes.size(); ++i)
00307 {
00308 s << indent << " nodes[" << i << "]: ";
00309 s << std::endl;
00310 s << indent;
00311 Printer< ::topological_nav_msgs::TopologicalMapNode_<ContainerAllocator> >::stream(s, indent + " ", v.nodes[i]);
00312 }
00313 s << indent << "edges[]" << std::endl;
00314 for (size_t i = 0; i < v.edges.size(); ++i)
00315 {
00316 s << indent << " edges[" << i << "]: ";
00317 s << std::endl;
00318 s << indent;
00319 Printer< ::topological_nav_msgs::TopologicalMapEdge_<ContainerAllocator> >::stream(s, indent + " ", v.edges[i]);
00320 }
00321 }
00322 };
00323
00324
00325 }
00326 }
00327
00328 #endif // TOPOLOGICAL_NAV_MSGS_MESSAGE_TOPOLOGICALGRAPH_H
00329