00001
00002 #ifndef GRAPH_MAPPING_MSGS_MESSAGE_NODEPOSES_H
00003 #define GRAPH_MAPPING_MSGS_MESSAGE_NODEPOSES_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 "geometry_msgs/Pose.h"
00014
00015 namespace graph_mapping_msgs
00016 {
00017 template <class ContainerAllocator>
00018 struct NodePoses_ : public ros::Message
00019 {
00020 typedef NodePoses_<ContainerAllocator> Type;
00021
00022 NodePoses_()
00023 : nodes()
00024 , poses()
00025 {
00026 }
00027
00028 NodePoses_(const ContainerAllocator& _alloc)
00029 : nodes(_alloc)
00030 , poses(_alloc)
00031 {
00032 }
00033
00034 typedef std::vector<uint32_t, typename ContainerAllocator::template rebind<uint32_t>::other > _nodes_type;
00035 std::vector<uint32_t, typename ContainerAllocator::template rebind<uint32_t>::other > nodes;
00036
00037 typedef std::vector< ::geometry_msgs::Pose_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::Pose_<ContainerAllocator> >::other > _poses_type;
00038 std::vector< ::geometry_msgs::Pose_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::Pose_<ContainerAllocator> >::other > poses;
00039
00040
00041 ROS_DEPRECATED uint32_t get_nodes_size() const { return (uint32_t)nodes.size(); }
00042 ROS_DEPRECATED void set_nodes_size(uint32_t size) { nodes.resize((size_t)size); }
00043 ROS_DEPRECATED void get_nodes_vec(std::vector<uint32_t, typename ContainerAllocator::template rebind<uint32_t>::other > & vec) const { vec = this->nodes; }
00044 ROS_DEPRECATED void set_nodes_vec(const std::vector<uint32_t, typename ContainerAllocator::template rebind<uint32_t>::other > & vec) { this->nodes = vec; }
00045 ROS_DEPRECATED uint32_t get_poses_size() const { return (uint32_t)poses.size(); }
00046 ROS_DEPRECATED void set_poses_size(uint32_t size) { poses.resize((size_t)size); }
00047 ROS_DEPRECATED void get_poses_vec(std::vector< ::geometry_msgs::Pose_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::Pose_<ContainerAllocator> >::other > & vec) const { vec = this->poses; }
00048 ROS_DEPRECATED void set_poses_vec(const std::vector< ::geometry_msgs::Pose_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::Pose_<ContainerAllocator> >::other > & vec) { this->poses = vec; }
00049 private:
00050 static const char* __s_getDataType_() { return "graph_mapping_msgs/NodePoses"; }
00051 public:
00052 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00053
00054 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00055
00056 private:
00057 static const char* __s_getMD5Sum_() { return "10146f24409c7b36494bc5b59c3624f1"; }
00058 public:
00059 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00060
00061 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00062
00063 private:
00064 static const char* __s_getMessageDefinition_() { return "# Represents optimized poses in a graph\n\
00065 uint32[] nodes\n\
00066 geometry_msgs/Pose[] poses\n\
00067 ================================================================================\n\
00068 MSG: geometry_msgs/Pose\n\
00069 # A representation of pose in free space, composed of postion and orientation. \n\
00070 Point position\n\
00071 Quaternion orientation\n\
00072 \n\
00073 ================================================================================\n\
00074 MSG: geometry_msgs/Point\n\
00075 # This contains the position of a point in free space\n\
00076 float64 x\n\
00077 float64 y\n\
00078 float64 z\n\
00079 \n\
00080 ================================================================================\n\
00081 MSG: geometry_msgs/Quaternion\n\
00082 # This represents an orientation in free space in quaternion form.\n\
00083 \n\
00084 float64 x\n\
00085 float64 y\n\
00086 float64 z\n\
00087 float64 w\n\
00088 \n\
00089 "; }
00090 public:
00091 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00092
00093 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00094
00095 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00096 {
00097 ros::serialization::OStream stream(write_ptr, 1000000000);
00098 ros::serialization::serialize(stream, nodes);
00099 ros::serialization::serialize(stream, poses);
00100 return stream.getData();
00101 }
00102
00103 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00104 {
00105 ros::serialization::IStream stream(read_ptr, 1000000000);
00106 ros::serialization::deserialize(stream, nodes);
00107 ros::serialization::deserialize(stream, poses);
00108 return stream.getData();
00109 }
00110
00111 ROS_DEPRECATED virtual uint32_t serializationLength() const
00112 {
00113 uint32_t size = 0;
00114 size += ros::serialization::serializationLength(nodes);
00115 size += ros::serialization::serializationLength(poses);
00116 return size;
00117 }
00118
00119 typedef boost::shared_ptr< ::graph_mapping_msgs::NodePoses_<ContainerAllocator> > Ptr;
00120 typedef boost::shared_ptr< ::graph_mapping_msgs::NodePoses_<ContainerAllocator> const> ConstPtr;
00121 };
00122 typedef ::graph_mapping_msgs::NodePoses_<std::allocator<void> > NodePoses;
00123
00124 typedef boost::shared_ptr< ::graph_mapping_msgs::NodePoses> NodePosesPtr;
00125 typedef boost::shared_ptr< ::graph_mapping_msgs::NodePoses const> NodePosesConstPtr;
00126
00127
00128 template<typename ContainerAllocator>
00129 std::ostream& operator<<(std::ostream& s, const ::graph_mapping_msgs::NodePoses_<ContainerAllocator> & v)
00130 {
00131 ros::message_operations::Printer< ::graph_mapping_msgs::NodePoses_<ContainerAllocator> >::stream(s, "", v);
00132 return s;}
00133
00134 }
00135
00136 namespace ros
00137 {
00138 namespace message_traits
00139 {
00140 template<class ContainerAllocator>
00141 struct MD5Sum< ::graph_mapping_msgs::NodePoses_<ContainerAllocator> > {
00142 static const char* value()
00143 {
00144 return "10146f24409c7b36494bc5b59c3624f1";
00145 }
00146
00147 static const char* value(const ::graph_mapping_msgs::NodePoses_<ContainerAllocator> &) { return value(); }
00148 static const uint64_t static_value1 = 0x10146f24409c7b36ULL;
00149 static const uint64_t static_value2 = 0x494bc5b59c3624f1ULL;
00150 };
00151
00152 template<class ContainerAllocator>
00153 struct DataType< ::graph_mapping_msgs::NodePoses_<ContainerAllocator> > {
00154 static const char* value()
00155 {
00156 return "graph_mapping_msgs/NodePoses";
00157 }
00158
00159 static const char* value(const ::graph_mapping_msgs::NodePoses_<ContainerAllocator> &) { return value(); }
00160 };
00161
00162 template<class ContainerAllocator>
00163 struct Definition< ::graph_mapping_msgs::NodePoses_<ContainerAllocator> > {
00164 static const char* value()
00165 {
00166 return "# Represents optimized poses in a graph\n\
00167 uint32[] nodes\n\
00168 geometry_msgs/Pose[] poses\n\
00169 ================================================================================\n\
00170 MSG: geometry_msgs/Pose\n\
00171 # A representation of pose in free space, composed of postion and orientation. \n\
00172 Point position\n\
00173 Quaternion orientation\n\
00174 \n\
00175 ================================================================================\n\
00176 MSG: geometry_msgs/Point\n\
00177 # This contains the position of a point in free space\n\
00178 float64 x\n\
00179 float64 y\n\
00180 float64 z\n\
00181 \n\
00182 ================================================================================\n\
00183 MSG: geometry_msgs/Quaternion\n\
00184 # This represents an orientation in free space in quaternion form.\n\
00185 \n\
00186 float64 x\n\
00187 float64 y\n\
00188 float64 z\n\
00189 float64 w\n\
00190 \n\
00191 ";
00192 }
00193
00194 static const char* value(const ::graph_mapping_msgs::NodePoses_<ContainerAllocator> &) { return value(); }
00195 };
00196
00197 }
00198 }
00199
00200 namespace ros
00201 {
00202 namespace serialization
00203 {
00204
00205 template<class ContainerAllocator> struct Serializer< ::graph_mapping_msgs::NodePoses_<ContainerAllocator> >
00206 {
00207 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00208 {
00209 stream.next(m.nodes);
00210 stream.next(m.poses);
00211 }
00212
00213 ROS_DECLARE_ALLINONE_SERIALIZER;
00214 };
00215 }
00216 }
00217
00218 namespace ros
00219 {
00220 namespace message_operations
00221 {
00222
00223 template<class ContainerAllocator>
00224 struct Printer< ::graph_mapping_msgs::NodePoses_<ContainerAllocator> >
00225 {
00226 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::graph_mapping_msgs::NodePoses_<ContainerAllocator> & v)
00227 {
00228 s << indent << "nodes[]" << std::endl;
00229 for (size_t i = 0; i < v.nodes.size(); ++i)
00230 {
00231 s << indent << " nodes[" << i << "]: ";
00232 Printer<uint32_t>::stream(s, indent + " ", v.nodes[i]);
00233 }
00234 s << indent << "poses[]" << std::endl;
00235 for (size_t i = 0; i < v.poses.size(); ++i)
00236 {
00237 s << indent << " poses[" << i << "]: ";
00238 s << std::endl;
00239 s << indent;
00240 Printer< ::geometry_msgs::Pose_<ContainerAllocator> >::stream(s, indent + " ", v.poses[i]);
00241 }
00242 }
00243 };
00244
00245
00246 }
00247 }
00248
00249 #endif // GRAPH_MAPPING_MSGS_MESSAGE_NODEPOSES_H
00250