Detection.h
Go to the documentation of this file.
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-groovy-cob_perception_common/doc_stacks/2013-03-08_15-00-12.727680/cob_perception_common/cob_object_detection_msgs/msg/Detection.msg */
00002 #ifndef COB_OBJECT_DETECTION_MSGS_MESSAGE_DETECTION_H
00003 #define COB_OBJECT_DETECTION_MSGS_MESSAGE_DETECTION_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 "std_msgs/Header.h"
00018 #include "cob_object_detection_msgs/Mask.h"
00019 #include "geometry_msgs/PoseStamped.h"
00020 #include "geometry_msgs/Point.h"
00021 
00022 namespace cob_object_detection_msgs
00023 {
00024 template <class ContainerAllocator>
00025 struct Detection_ {
00026   typedef Detection_<ContainerAllocator> Type;
00027 
00028   Detection_()
00029   : header()
00030   , label()
00031   , detector()
00032   , score(0.0)
00033   , mask()
00034   , pose()
00035   , bounding_box_lwh()
00036   {
00037   }
00038 
00039   Detection_(const ContainerAllocator& _alloc)
00040   : header(_alloc)
00041   , label(_alloc)
00042   , detector(_alloc)
00043   , score(0.0)
00044   , mask(_alloc)
00045   , pose(_alloc)
00046   , bounding_box_lwh(_alloc)
00047   {
00048   }
00049 
00050   typedef  ::std_msgs::Header_<ContainerAllocator>  _header_type;
00051    ::std_msgs::Header_<ContainerAllocator>  header;
00052 
00053   typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other >  _label_type;
00054   std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other >  label;
00055 
00056   typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other >  _detector_type;
00057   std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other >  detector;
00058 
00059   typedef float _score_type;
00060   float score;
00061 
00062   typedef  ::cob_object_detection_msgs::Mask_<ContainerAllocator>  _mask_type;
00063    ::cob_object_detection_msgs::Mask_<ContainerAllocator>  mask;
00064 
00065   typedef  ::geometry_msgs::PoseStamped_<ContainerAllocator>  _pose_type;
00066    ::geometry_msgs::PoseStamped_<ContainerAllocator>  pose;
00067 
00068   typedef  ::geometry_msgs::Point_<ContainerAllocator>  _bounding_box_lwh_type;
00069    ::geometry_msgs::Point_<ContainerAllocator>  bounding_box_lwh;
00070 
00071 
00072   typedef boost::shared_ptr< ::cob_object_detection_msgs::Detection_<ContainerAllocator> > Ptr;
00073   typedef boost::shared_ptr< ::cob_object_detection_msgs::Detection_<ContainerAllocator>  const> ConstPtr;
00074   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00075 }; // struct Detection
00076 typedef  ::cob_object_detection_msgs::Detection_<std::allocator<void> > Detection;
00077 
00078 typedef boost::shared_ptr< ::cob_object_detection_msgs::Detection> DetectionPtr;
00079 typedef boost::shared_ptr< ::cob_object_detection_msgs::Detection const> DetectionConstPtr;
00080 
00081 
00082 template<typename ContainerAllocator>
00083 std::ostream& operator<<(std::ostream& s, const  ::cob_object_detection_msgs::Detection_<ContainerAllocator> & v)
00084 {
00085   ros::message_operations::Printer< ::cob_object_detection_msgs::Detection_<ContainerAllocator> >::stream(s, "", v);
00086   return s;}
00087 
00088 } // namespace cob_object_detection_msgs
00089 
00090 namespace ros
00091 {
00092 namespace message_traits
00093 {
00094 template<class ContainerAllocator> struct IsMessage< ::cob_object_detection_msgs::Detection_<ContainerAllocator> > : public TrueType {};
00095 template<class ContainerAllocator> struct IsMessage< ::cob_object_detection_msgs::Detection_<ContainerAllocator>  const> : public TrueType {};
00096 template<class ContainerAllocator>
00097 struct MD5Sum< ::cob_object_detection_msgs::Detection_<ContainerAllocator> > {
00098   static const char* value() 
00099   {
00100     return "0e10cbf79379d085e3459569bbe22c63";
00101   }
00102 
00103   static const char* value(const  ::cob_object_detection_msgs::Detection_<ContainerAllocator> &) { return value(); } 
00104   static const uint64_t static_value1 = 0x0e10cbf79379d085ULL;
00105   static const uint64_t static_value2 = 0xe3459569bbe22c63ULL;
00106 };
00107 
00108 template<class ContainerAllocator>
00109 struct DataType< ::cob_object_detection_msgs::Detection_<ContainerAllocator> > {
00110   static const char* value() 
00111   {
00112     return "cob_object_detection_msgs/Detection";
00113   }
00114 
00115   static const char* value(const  ::cob_object_detection_msgs::Detection_<ContainerAllocator> &) { return value(); } 
00116 };
00117 
00118 template<class ContainerAllocator>
00119 struct Definition< ::cob_object_detection_msgs::Detection_<ContainerAllocator> > {
00120   static const char* value() 
00121   {
00122     return "Header header\n\
00123 string label\n\
00124 string detector\n\
00125 float32 score\n\
00126 Mask mask\n\
00127 geometry_msgs/PoseStamped pose\n\
00128 geometry_msgs/Point bounding_box_lwh\n\
00129 \n\
00130 ================================================================================\n\
00131 MSG: std_msgs/Header\n\
00132 # Standard metadata for higher-level stamped data types.\n\
00133 # This is generally used to communicate timestamped data \n\
00134 # in a particular coordinate frame.\n\
00135 # \n\
00136 # sequence ID: consecutively increasing ID \n\
00137 uint32 seq\n\
00138 #Two-integer timestamp that is expressed as:\n\
00139 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00140 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00141 # time-handling sugar is provided by the client library\n\
00142 time stamp\n\
00143 #Frame this data is associated with\n\
00144 # 0: no frame\n\
00145 # 1: global frame\n\
00146 string frame_id\n\
00147 \n\
00148 ================================================================================\n\
00149 MSG: cob_object_detection_msgs/Mask\n\
00150 # this message is used to mark where an object is present in an image\n\
00151 # this can be done either by a roi region on the image (less precise) or a mask (more precise)\n\
00152 \n\
00153 Rect roi\n\
00154 \n\
00155 # in the case when mask is used, 'roi' specifies the image region and 'mask'\n\
00156 # (which should be of the same size) a binary mask in that region\n\
00157 sensor_msgs/Image mask\n\
00158 \n\
00159 # in the case there is 3D data available, 'indices' are used to index the \n\
00160 # part of the point cloud representing the object\n\
00161 #pcl/PointIndices indices\n\
00162 \n\
00163 ================================================================================\n\
00164 MSG: cob_object_detection_msgs/Rect\n\
00165 int32 x\n\
00166 int32 y\n\
00167 int32 width\n\
00168 int32 height\n\
00169 \n\
00170 ================================================================================\n\
00171 MSG: sensor_msgs/Image\n\
00172 # This message contains an uncompressed image\n\
00173 # (0, 0) is at top-left corner of image\n\
00174 #\n\
00175 \n\
00176 Header header        # Header timestamp should be acquisition time of image\n\
00177                      # Header frame_id should be optical frame of camera\n\
00178                      # origin of frame should be optical center of cameara\n\
00179                      # +x should point to the right in the image\n\
00180                      # +y should point down in the image\n\
00181                      # +z should point into to plane of the image\n\
00182                      # If the frame_id here and the frame_id of the CameraInfo\n\
00183                      # message associated with the image conflict\n\
00184                      # the behavior is undefined\n\
00185 \n\
00186 uint32 height         # image height, that is, number of rows\n\
00187 uint32 width          # image width, that is, number of columns\n\
00188 \n\
00189 # The legal values for encoding are in file src/image_encodings.cpp\n\
00190 # If you want to standardize a new string format, join\n\
00191 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.\n\
00192 \n\
00193 string encoding       # Encoding of pixels -- channel meaning, ordering, size\n\
00194                       # taken from the list of strings in include/sensor_msgs/image_encodings.h\n\
00195 \n\
00196 uint8 is_bigendian    # is this data bigendian?\n\
00197 uint32 step           # Full row length in bytes\n\
00198 uint8[] data          # actual matrix data, size is (step * rows)\n\
00199 \n\
00200 ================================================================================\n\
00201 MSG: geometry_msgs/PoseStamped\n\
00202 # A Pose with reference coordinate frame and timestamp\n\
00203 Header header\n\
00204 Pose pose\n\
00205 \n\
00206 ================================================================================\n\
00207 MSG: geometry_msgs/Pose\n\
00208 # A representation of pose in free space, composed of postion and orientation. \n\
00209 Point position\n\
00210 Quaternion orientation\n\
00211 \n\
00212 ================================================================================\n\
00213 MSG: geometry_msgs/Point\n\
00214 # This contains the position of a point in free space\n\
00215 float64 x\n\
00216 float64 y\n\
00217 float64 z\n\
00218 \n\
00219 ================================================================================\n\
00220 MSG: geometry_msgs/Quaternion\n\
00221 # This represents an orientation in free space in quaternion form.\n\
00222 \n\
00223 float64 x\n\
00224 float64 y\n\
00225 float64 z\n\
00226 float64 w\n\
00227 \n\
00228 ";
00229   }
00230 
00231   static const char* value(const  ::cob_object_detection_msgs::Detection_<ContainerAllocator> &) { return value(); } 
00232 };
00233 
00234 template<class ContainerAllocator> struct HasHeader< ::cob_object_detection_msgs::Detection_<ContainerAllocator> > : public TrueType {};
00235 template<class ContainerAllocator> struct HasHeader< const ::cob_object_detection_msgs::Detection_<ContainerAllocator> > : public TrueType {};
00236 } // namespace message_traits
00237 } // namespace ros
00238 
00239 namespace ros
00240 {
00241 namespace serialization
00242 {
00243 
00244 template<class ContainerAllocator> struct Serializer< ::cob_object_detection_msgs::Detection_<ContainerAllocator> >
00245 {
00246   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00247   {
00248     stream.next(m.header);
00249     stream.next(m.label);
00250     stream.next(m.detector);
00251     stream.next(m.score);
00252     stream.next(m.mask);
00253     stream.next(m.pose);
00254     stream.next(m.bounding_box_lwh);
00255   }
00256 
00257   ROS_DECLARE_ALLINONE_SERIALIZER;
00258 }; // struct Detection_
00259 } // namespace serialization
00260 } // namespace ros
00261 
00262 namespace ros
00263 {
00264 namespace message_operations
00265 {
00266 
00267 template<class ContainerAllocator>
00268 struct Printer< ::cob_object_detection_msgs::Detection_<ContainerAllocator> >
00269 {
00270   template<typename Stream> static void stream(Stream& s, const std::string& indent, const  ::cob_object_detection_msgs::Detection_<ContainerAllocator> & v) 
00271   {
00272     s << indent << "header: ";
00273 s << std::endl;
00274     Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + "  ", v.header);
00275     s << indent << "label: ";
00276     Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + "  ", v.label);
00277     s << indent << "detector: ";
00278     Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + "  ", v.detector);
00279     s << indent << "score: ";
00280     Printer<float>::stream(s, indent + "  ", v.score);
00281     s << indent << "mask: ";
00282 s << std::endl;
00283     Printer< ::cob_object_detection_msgs::Mask_<ContainerAllocator> >::stream(s, indent + "  ", v.mask);
00284     s << indent << "pose: ";
00285 s << std::endl;
00286     Printer< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::stream(s, indent + "  ", v.pose);
00287     s << indent << "bounding_box_lwh: ";
00288 s << std::endl;
00289     Printer< ::geometry_msgs::Point_<ContainerAllocator> >::stream(s, indent + "  ", v.bounding_box_lwh);
00290   }
00291 };
00292 
00293 
00294 } // namespace message_operations
00295 } // namespace ros
00296 
00297 #endif // COB_OBJECT_DETECTION_MSGS_MESSAGE_DETECTION_H
00298 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends


cob_object_detection_msgs
Author(s): Florian Weisshardt
autogenerated on Fri Mar 8 2013 15:04:09