$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-common_msgs/doc_stacks/2013-03-01_14-58-52.505545/common_msgs/sensor_msgs/msg/RegionOfInterest.msg */ 00002 #ifndef SENSOR_MSGS_MESSAGE_REGIONOFINTEREST_H 00003 #define SENSOR_MSGS_MESSAGE_REGIONOFINTEREST_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 00018 namespace sensor_msgs 00019 { 00020 template <class ContainerAllocator> 00021 struct RegionOfInterest_ { 00022 typedef RegionOfInterest_<ContainerAllocator> Type; 00023 00024 RegionOfInterest_() 00025 : x_offset(0) 00026 , y_offset(0) 00027 , height(0) 00028 , width(0) 00029 , do_rectify(false) 00030 { 00031 } 00032 00033 RegionOfInterest_(const ContainerAllocator& _alloc) 00034 : x_offset(0) 00035 , y_offset(0) 00036 , height(0) 00037 , width(0) 00038 , do_rectify(false) 00039 { 00040 } 00041 00042 typedef uint32_t _x_offset_type; 00043 uint32_t x_offset; 00044 00045 typedef uint32_t _y_offset_type; 00046 uint32_t y_offset; 00047 00048 typedef uint32_t _height_type; 00049 uint32_t height; 00050 00051 typedef uint32_t _width_type; 00052 uint32_t width; 00053 00054 typedef uint8_t _do_rectify_type; 00055 uint8_t do_rectify; 00056 00057 00058 private: 00059 static const char* __s_getDataType_() { return "sensor_msgs/RegionOfInterest"; } 00060 public: 00061 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00062 00063 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00064 00065 private: 00066 static const char* __s_getMD5Sum_() { return "bdb633039d588fcccb441a4d43ccfe09"; } 00067 public: 00068 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00069 00070 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00071 00072 private: 00073 static const char* __s_getMessageDefinition_() { return "# This message is used to specify a region of interest within an image.\n\ 00074 #\n\ 00075 # When used to specify the ROI setting of the camera when the image was\n\ 00076 # taken, the height and width fields should either match the height and\n\ 00077 # width fields for the associated image; or height = width = 0\n\ 00078 # indicates that the full resolution image was captured.\n\ 00079 \n\ 00080 uint32 x_offset # Leftmost pixel of the ROI\n\ 00081 # (0 if the ROI includes the left edge of the image)\n\ 00082 uint32 y_offset # Topmost pixel of the ROI\n\ 00083 # (0 if the ROI includes the top edge of the image)\n\ 00084 uint32 height # Height of ROI\n\ 00085 uint32 width # Width of ROI\n\ 00086 \n\ 00087 # True if a distinct rectified ROI should be calculated from the \"raw\"\n\ 00088 # ROI in this message. Typically this should be False if the full image\n\ 00089 # is captured (ROI not used), and True if a subwindow is captured (ROI\n\ 00090 # used).\n\ 00091 bool do_rectify\n\ 00092 \n\ 00093 "; } 00094 public: 00095 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00096 00097 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00098 00099 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00100 { 00101 ros::serialization::OStream stream(write_ptr, 1000000000); 00102 ros::serialization::serialize(stream, x_offset); 00103 ros::serialization::serialize(stream, y_offset); 00104 ros::serialization::serialize(stream, height); 00105 ros::serialization::serialize(stream, width); 00106 ros::serialization::serialize(stream, do_rectify); 00107 return stream.getData(); 00108 } 00109 00110 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00111 { 00112 ros::serialization::IStream stream(read_ptr, 1000000000); 00113 ros::serialization::deserialize(stream, x_offset); 00114 ros::serialization::deserialize(stream, y_offset); 00115 ros::serialization::deserialize(stream, height); 00116 ros::serialization::deserialize(stream, width); 00117 ros::serialization::deserialize(stream, do_rectify); 00118 return stream.getData(); 00119 } 00120 00121 ROS_DEPRECATED virtual uint32_t serializationLength() const 00122 { 00123 uint32_t size = 0; 00124 size += ros::serialization::serializationLength(x_offset); 00125 size += ros::serialization::serializationLength(y_offset); 00126 size += ros::serialization::serializationLength(height); 00127 size += ros::serialization::serializationLength(width); 00128 size += ros::serialization::serializationLength(do_rectify); 00129 return size; 00130 } 00131 00132 typedef boost::shared_ptr< ::sensor_msgs::RegionOfInterest_<ContainerAllocator> > Ptr; 00133 typedef boost::shared_ptr< ::sensor_msgs::RegionOfInterest_<ContainerAllocator> const> ConstPtr; 00134 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00135 }; // struct RegionOfInterest 00136 typedef ::sensor_msgs::RegionOfInterest_<std::allocator<void> > RegionOfInterest; 00137 00138 typedef boost::shared_ptr< ::sensor_msgs::RegionOfInterest> RegionOfInterestPtr; 00139 typedef boost::shared_ptr< ::sensor_msgs::RegionOfInterest const> RegionOfInterestConstPtr; 00140 00141 00142 template<typename ContainerAllocator> 00143 std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::RegionOfInterest_<ContainerAllocator> & v) 00144 { 00145 ros::message_operations::Printer< ::sensor_msgs::RegionOfInterest_<ContainerAllocator> >::stream(s, "", v); 00146 return s;} 00147 00148 } // namespace sensor_msgs 00149 00150 namespace ros 00151 { 00152 namespace message_traits 00153 { 00154 template<class ContainerAllocator> struct IsMessage< ::sensor_msgs::RegionOfInterest_<ContainerAllocator> > : public TrueType {}; 00155 template<class ContainerAllocator> struct IsMessage< ::sensor_msgs::RegionOfInterest_<ContainerAllocator> const> : public TrueType {}; 00156 template<class ContainerAllocator> 00157 struct MD5Sum< ::sensor_msgs::RegionOfInterest_<ContainerAllocator> > { 00158 static const char* value() 00159 { 00160 return "bdb633039d588fcccb441a4d43ccfe09"; 00161 } 00162 00163 static const char* value(const ::sensor_msgs::RegionOfInterest_<ContainerAllocator> &) { return value(); } 00164 static const uint64_t static_value1 = 0xbdb633039d588fccULL; 00165 static const uint64_t static_value2 = 0xcb441a4d43ccfe09ULL; 00166 }; 00167 00168 template<class ContainerAllocator> 00169 struct DataType< ::sensor_msgs::RegionOfInterest_<ContainerAllocator> > { 00170 static const char* value() 00171 { 00172 return "sensor_msgs/RegionOfInterest"; 00173 } 00174 00175 static const char* value(const ::sensor_msgs::RegionOfInterest_<ContainerAllocator> &) { return value(); } 00176 }; 00177 00178 template<class ContainerAllocator> 00179 struct Definition< ::sensor_msgs::RegionOfInterest_<ContainerAllocator> > { 00180 static const char* value() 00181 { 00182 return "# This message is used to specify a region of interest within an image.\n\ 00183 #\n\ 00184 # When used to specify the ROI setting of the camera when the image was\n\ 00185 # taken, the height and width fields should either match the height and\n\ 00186 # width fields for the associated image; or height = width = 0\n\ 00187 # indicates that the full resolution image was captured.\n\ 00188 \n\ 00189 uint32 x_offset # Leftmost pixel of the ROI\n\ 00190 # (0 if the ROI includes the left edge of the image)\n\ 00191 uint32 y_offset # Topmost pixel of the ROI\n\ 00192 # (0 if the ROI includes the top edge of the image)\n\ 00193 uint32 height # Height of ROI\n\ 00194 uint32 width # Width of ROI\n\ 00195 \n\ 00196 # True if a distinct rectified ROI should be calculated from the \"raw\"\n\ 00197 # ROI in this message. Typically this should be False if the full image\n\ 00198 # is captured (ROI not used), and True if a subwindow is captured (ROI\n\ 00199 # used).\n\ 00200 bool do_rectify\n\ 00201 \n\ 00202 "; 00203 } 00204 00205 static const char* value(const ::sensor_msgs::RegionOfInterest_<ContainerAllocator> &) { return value(); } 00206 }; 00207 00208 template<class ContainerAllocator> struct IsFixedSize< ::sensor_msgs::RegionOfInterest_<ContainerAllocator> > : public TrueType {}; 00209 } // namespace message_traits 00210 } // namespace ros 00211 00212 namespace ros 00213 { 00214 namespace serialization 00215 { 00216 00217 template<class ContainerAllocator> struct Serializer< ::sensor_msgs::RegionOfInterest_<ContainerAllocator> > 00218 { 00219 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00220 { 00221 stream.next(m.x_offset); 00222 stream.next(m.y_offset); 00223 stream.next(m.height); 00224 stream.next(m.width); 00225 stream.next(m.do_rectify); 00226 } 00227 00228 ROS_DECLARE_ALLINONE_SERIALIZER; 00229 }; // struct RegionOfInterest_ 00230 } // namespace serialization 00231 } // namespace ros 00232 00233 namespace ros 00234 { 00235 namespace message_operations 00236 { 00237 00238 template<class ContainerAllocator> 00239 struct Printer< ::sensor_msgs::RegionOfInterest_<ContainerAllocator> > 00240 { 00241 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::RegionOfInterest_<ContainerAllocator> & v) 00242 { 00243 s << indent << "x_offset: "; 00244 Printer<uint32_t>::stream(s, indent + " ", v.x_offset); 00245 s << indent << "y_offset: "; 00246 Printer<uint32_t>::stream(s, indent + " ", v.y_offset); 00247 s << indent << "height: "; 00248 Printer<uint32_t>::stream(s, indent + " ", v.height); 00249 s << indent << "width: "; 00250 Printer<uint32_t>::stream(s, indent + " ", v.width); 00251 s << indent << "do_rectify: "; 00252 Printer<uint8_t>::stream(s, indent + " ", v.do_rectify); 00253 } 00254 }; 00255 00256 00257 } // namespace message_operations 00258 } // namespace ros 00259 00260 #endif // SENSOR_MSGS_MESSAGE_REGIONOFINTEREST_H 00261