$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-tu-darmstadt-ros-pkg/doc_stacks/2013-03-05_12-22-58.304137/hector_navigation/hector_elevation_msgs/msg/ElevationMapMetaData.msg */ 00002 #ifndef HECTOR_ELEVATION_MSGS_MESSAGE_ELEVATIONMAPMETADATA_H 00003 #define HECTOR_ELEVATION_MSGS_MESSAGE_ELEVATIONMAPMETADATA_H 00004 #include <string> 00005 #include <vector> 00006 #include <map> 00007 #include <ostream> 00008 #include "ros/serialization.h" 00009 #include "ros/builtin_message_traits.h" 00010 #include "ros/message_operations.h" 00011 #include "ros/time.h" 00012 00013 #include "ros/macros.h" 00014 00015 #include "ros/assert.h" 00016 00017 #include "geometry_msgs/Pose.h" 00018 00019 namespace hector_elevation_msgs 00020 { 00021 template <class ContainerAllocator> 00022 struct ElevationMapMetaData_ { 00023 typedef ElevationMapMetaData_<ContainerAllocator> Type; 00024 00025 ElevationMapMetaData_() 00026 : map_load_time() 00027 , resolution_xy(0.0) 00028 , resolution_z(0.0) 00029 , min_elevation(0.0) 00030 , max_elevation(0.0) 00031 , zero_elevation(0) 00032 , width(0) 00033 , height(0) 00034 , origin() 00035 { 00036 } 00037 00038 ElevationMapMetaData_(const ContainerAllocator& _alloc) 00039 : map_load_time() 00040 , resolution_xy(0.0) 00041 , resolution_z(0.0) 00042 , min_elevation(0.0) 00043 , max_elevation(0.0) 00044 , zero_elevation(0) 00045 , width(0) 00046 , height(0) 00047 , origin(_alloc) 00048 { 00049 } 00050 00051 typedef ros::Time _map_load_time_type; 00052 ros::Time map_load_time; 00053 00054 typedef double _resolution_xy_type; 00055 double resolution_xy; 00056 00057 typedef double _resolution_z_type; 00058 double resolution_z; 00059 00060 typedef double _min_elevation_type; 00061 double min_elevation; 00062 00063 typedef double _max_elevation_type; 00064 double max_elevation; 00065 00066 typedef int16_t _zero_elevation_type; 00067 int16_t zero_elevation; 00068 00069 typedef uint32_t _width_type; 00070 uint32_t width; 00071 00072 typedef uint32_t _height_type; 00073 uint32_t height; 00074 00075 typedef ::geometry_msgs::Pose_<ContainerAllocator> _origin_type; 00076 ::geometry_msgs::Pose_<ContainerAllocator> origin; 00077 00078 00079 private: 00080 static const char* __s_getDataType_() { return "hector_elevation_msgs/ElevationMapMetaData"; } 00081 public: 00082 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00083 00084 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00085 00086 private: 00087 static const char* __s_getMD5Sum_() { return "6c887873faf3a1d55d884bdcc92b9241"; } 00088 public: 00089 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00090 00091 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00092 00093 private: 00094 static const char* __s_getMessageDefinition_() { return "# This hold basic information about the characterists of the EvaluationGrid\n\ 00095 \n\ 00096 # The time at which the map was loaded\n\ 00097 time map_load_time\n\ 00098 # Map resolution in xy plane [m/cell]\n\ 00099 float64 resolution_xy\n\ 00100 # Map resolution in height [m/cell]\n\ 00101 float64 resolution_z\n\ 00102 # min observed height [m]\n\ 00103 float64 min_elevation\n\ 00104 # max observed height [m]\n\ 00105 float64 max_elevation\n\ 00106 # Height zero value. For example 16384.\n\ 00107 int16 zero_elevation\n\ 00108 # Map width [cells]\n\ 00109 uint32 width\n\ 00110 # Map height [cells]\n\ 00111 uint32 height\n\ 00112 # The origin of the map [m, m, rad]. This is the real-world pose of the\n\ 00113 # cell (0,0) in the map.\n\ 00114 geometry_msgs/Pose origin\n\ 00115 \n\ 00116 \n\ 00117 \n\ 00118 ================================================================================\n\ 00119 MSG: geometry_msgs/Pose\n\ 00120 # A representation of pose in free space, composed of postion and orientation. \n\ 00121 Point position\n\ 00122 Quaternion orientation\n\ 00123 \n\ 00124 ================================================================================\n\ 00125 MSG: geometry_msgs/Point\n\ 00126 # This contains the position of a point in free space\n\ 00127 float64 x\n\ 00128 float64 y\n\ 00129 float64 z\n\ 00130 \n\ 00131 ================================================================================\n\ 00132 MSG: geometry_msgs/Quaternion\n\ 00133 # This represents an orientation in free space in quaternion form.\n\ 00134 \n\ 00135 float64 x\n\ 00136 float64 y\n\ 00137 float64 z\n\ 00138 float64 w\n\ 00139 \n\ 00140 "; } 00141 public: 00142 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00143 00144 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00145 00146 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00147 { 00148 ros::serialization::OStream stream(write_ptr, 1000000000); 00149 ros::serialization::serialize(stream, map_load_time); 00150 ros::serialization::serialize(stream, resolution_xy); 00151 ros::serialization::serialize(stream, resolution_z); 00152 ros::serialization::serialize(stream, min_elevation); 00153 ros::serialization::serialize(stream, max_elevation); 00154 ros::serialization::serialize(stream, zero_elevation); 00155 ros::serialization::serialize(stream, width); 00156 ros::serialization::serialize(stream, height); 00157 ros::serialization::serialize(stream, origin); 00158 return stream.getData(); 00159 } 00160 00161 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00162 { 00163 ros::serialization::IStream stream(read_ptr, 1000000000); 00164 ros::serialization::deserialize(stream, map_load_time); 00165 ros::serialization::deserialize(stream, resolution_xy); 00166 ros::serialization::deserialize(stream, resolution_z); 00167 ros::serialization::deserialize(stream, min_elevation); 00168 ros::serialization::deserialize(stream, max_elevation); 00169 ros::serialization::deserialize(stream, zero_elevation); 00170 ros::serialization::deserialize(stream, width); 00171 ros::serialization::deserialize(stream, height); 00172 ros::serialization::deserialize(stream, origin); 00173 return stream.getData(); 00174 } 00175 00176 ROS_DEPRECATED virtual uint32_t serializationLength() const 00177 { 00178 uint32_t size = 0; 00179 size += ros::serialization::serializationLength(map_load_time); 00180 size += ros::serialization::serializationLength(resolution_xy); 00181 size += ros::serialization::serializationLength(resolution_z); 00182 size += ros::serialization::serializationLength(min_elevation); 00183 size += ros::serialization::serializationLength(max_elevation); 00184 size += ros::serialization::serializationLength(zero_elevation); 00185 size += ros::serialization::serializationLength(width); 00186 size += ros::serialization::serializationLength(height); 00187 size += ros::serialization::serializationLength(origin); 00188 return size; 00189 } 00190 00191 typedef boost::shared_ptr< ::hector_elevation_msgs::ElevationMapMetaData_<ContainerAllocator> > Ptr; 00192 typedef boost::shared_ptr< ::hector_elevation_msgs::ElevationMapMetaData_<ContainerAllocator> const> ConstPtr; 00193 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00194 }; // struct ElevationMapMetaData 00195 typedef ::hector_elevation_msgs::ElevationMapMetaData_<std::allocator<void> > ElevationMapMetaData; 00196 00197 typedef boost::shared_ptr< ::hector_elevation_msgs::ElevationMapMetaData> ElevationMapMetaDataPtr; 00198 typedef boost::shared_ptr< ::hector_elevation_msgs::ElevationMapMetaData const> ElevationMapMetaDataConstPtr; 00199 00200 00201 template<typename ContainerAllocator> 00202 std::ostream& operator<<(std::ostream& s, const ::hector_elevation_msgs::ElevationMapMetaData_<ContainerAllocator> & v) 00203 { 00204 ros::message_operations::Printer< ::hector_elevation_msgs::ElevationMapMetaData_<ContainerAllocator> >::stream(s, "", v); 00205 return s;} 00206 00207 } // namespace hector_elevation_msgs 00208 00209 namespace ros 00210 { 00211 namespace message_traits 00212 { 00213 template<class ContainerAllocator> struct IsMessage< ::hector_elevation_msgs::ElevationMapMetaData_<ContainerAllocator> > : public TrueType {}; 00214 template<class ContainerAllocator> struct IsMessage< ::hector_elevation_msgs::ElevationMapMetaData_<ContainerAllocator> const> : public TrueType {}; 00215 template<class ContainerAllocator> 00216 struct MD5Sum< ::hector_elevation_msgs::ElevationMapMetaData_<ContainerAllocator> > { 00217 static const char* value() 00218 { 00219 return "6c887873faf3a1d55d884bdcc92b9241"; 00220 } 00221 00222 static const char* value(const ::hector_elevation_msgs::ElevationMapMetaData_<ContainerAllocator> &) { return value(); } 00223 static const uint64_t static_value1 = 0x6c887873faf3a1d5ULL; 00224 static const uint64_t static_value2 = 0x5d884bdcc92b9241ULL; 00225 }; 00226 00227 template<class ContainerAllocator> 00228 struct DataType< ::hector_elevation_msgs::ElevationMapMetaData_<ContainerAllocator> > { 00229 static const char* value() 00230 { 00231 return "hector_elevation_msgs/ElevationMapMetaData"; 00232 } 00233 00234 static const char* value(const ::hector_elevation_msgs::ElevationMapMetaData_<ContainerAllocator> &) { return value(); } 00235 }; 00236 00237 template<class ContainerAllocator> 00238 struct Definition< ::hector_elevation_msgs::ElevationMapMetaData_<ContainerAllocator> > { 00239 static const char* value() 00240 { 00241 return "# This hold basic information about the characterists of the EvaluationGrid\n\ 00242 \n\ 00243 # The time at which the map was loaded\n\ 00244 time map_load_time\n\ 00245 # Map resolution in xy plane [m/cell]\n\ 00246 float64 resolution_xy\n\ 00247 # Map resolution in height [m/cell]\n\ 00248 float64 resolution_z\n\ 00249 # min observed height [m]\n\ 00250 float64 min_elevation\n\ 00251 # max observed height [m]\n\ 00252 float64 max_elevation\n\ 00253 # Height zero value. For example 16384.\n\ 00254 int16 zero_elevation\n\ 00255 # Map width [cells]\n\ 00256 uint32 width\n\ 00257 # Map height [cells]\n\ 00258 uint32 height\n\ 00259 # The origin of the map [m, m, rad]. This is the real-world pose of the\n\ 00260 # cell (0,0) in the map.\n\ 00261 geometry_msgs/Pose origin\n\ 00262 \n\ 00263 \n\ 00264 \n\ 00265 ================================================================================\n\ 00266 MSG: geometry_msgs/Pose\n\ 00267 # A representation of pose in free space, composed of postion and orientation. \n\ 00268 Point position\n\ 00269 Quaternion orientation\n\ 00270 \n\ 00271 ================================================================================\n\ 00272 MSG: geometry_msgs/Point\n\ 00273 # This contains the position of a point in free space\n\ 00274 float64 x\n\ 00275 float64 y\n\ 00276 float64 z\n\ 00277 \n\ 00278 ================================================================================\n\ 00279 MSG: geometry_msgs/Quaternion\n\ 00280 # This represents an orientation in free space in quaternion form.\n\ 00281 \n\ 00282 float64 x\n\ 00283 float64 y\n\ 00284 float64 z\n\ 00285 float64 w\n\ 00286 \n\ 00287 "; 00288 } 00289 00290 static const char* value(const ::hector_elevation_msgs::ElevationMapMetaData_<ContainerAllocator> &) { return value(); } 00291 }; 00292 00293 template<class ContainerAllocator> struct IsFixedSize< ::hector_elevation_msgs::ElevationMapMetaData_<ContainerAllocator> > : public TrueType {}; 00294 } // namespace message_traits 00295 } // namespace ros 00296 00297 namespace ros 00298 { 00299 namespace serialization 00300 { 00301 00302 template<class ContainerAllocator> struct Serializer< ::hector_elevation_msgs::ElevationMapMetaData_<ContainerAllocator> > 00303 { 00304 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00305 { 00306 stream.next(m.map_load_time); 00307 stream.next(m.resolution_xy); 00308 stream.next(m.resolution_z); 00309 stream.next(m.min_elevation); 00310 stream.next(m.max_elevation); 00311 stream.next(m.zero_elevation); 00312 stream.next(m.width); 00313 stream.next(m.height); 00314 stream.next(m.origin); 00315 } 00316 00317 ROS_DECLARE_ALLINONE_SERIALIZER; 00318 }; // struct ElevationMapMetaData_ 00319 } // namespace serialization 00320 } // namespace ros 00321 00322 namespace ros 00323 { 00324 namespace message_operations 00325 { 00326 00327 template<class ContainerAllocator> 00328 struct Printer< ::hector_elevation_msgs::ElevationMapMetaData_<ContainerAllocator> > 00329 { 00330 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::hector_elevation_msgs::ElevationMapMetaData_<ContainerAllocator> & v) 00331 { 00332 s << indent << "map_load_time: "; 00333 Printer<ros::Time>::stream(s, indent + " ", v.map_load_time); 00334 s << indent << "resolution_xy: "; 00335 Printer<double>::stream(s, indent + " ", v.resolution_xy); 00336 s << indent << "resolution_z: "; 00337 Printer<double>::stream(s, indent + " ", v.resolution_z); 00338 s << indent << "min_elevation: "; 00339 Printer<double>::stream(s, indent + " ", v.min_elevation); 00340 s << indent << "max_elevation: "; 00341 Printer<double>::stream(s, indent + " ", v.max_elevation); 00342 s << indent << "zero_elevation: "; 00343 Printer<int16_t>::stream(s, indent + " ", v.zero_elevation); 00344 s << indent << "width: "; 00345 Printer<uint32_t>::stream(s, indent + " ", v.width); 00346 s << indent << "height: "; 00347 Printer<uint32_t>::stream(s, indent + " ", v.height); 00348 s << indent << "origin: "; 00349 s << std::endl; 00350 Printer< ::geometry_msgs::Pose_<ContainerAllocator> >::stream(s, indent + " ", v.origin); 00351 } 00352 }; 00353 00354 00355 } // namespace message_operations 00356 } // namespace ros 00357 00358 #endif // HECTOR_ELEVATION_MSGS_MESSAGE_ELEVATIONMAPMETADATA_H 00359