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