00001
00002 #ifndef SENSOR_MSGS_MESSAGE_CAMERAINFO_H
00003 #define SENSOR_MSGS_MESSAGE_CAMERAINFO_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 "sensor_msgs/RegionOfInterest.h"
00019
00020 namespace sensor_msgs
00021 {
00022 template <class ContainerAllocator>
00023 struct CameraInfo_ {
00024 typedef CameraInfo_<ContainerAllocator> Type;
00025
00026 CameraInfo_()
00027 : header()
00028 , height(0)
00029 , width(0)
00030 , distortion_model()
00031 , D()
00032 , K()
00033 , R()
00034 , P()
00035 , binning_x(0)
00036 , binning_y(0)
00037 , roi()
00038 {
00039 K.assign(0.0);
00040 R.assign(0.0);
00041 P.assign(0.0);
00042 }
00043
00044 CameraInfo_(const ContainerAllocator& _alloc)
00045 : header(_alloc)
00046 , height(0)
00047 , width(0)
00048 , distortion_model(_alloc)
00049 , D(_alloc)
00050 , K()
00051 , R()
00052 , P()
00053 , binning_x(0)
00054 , binning_y(0)
00055 , roi(_alloc)
00056 {
00057 K.assign(0.0);
00058 R.assign(0.0);
00059 P.assign(0.0);
00060 }
00061
00062 typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
00063 ::std_msgs::Header_<ContainerAllocator> header;
00064
00065 typedef uint32_t _height_type;
00066 uint32_t height;
00067
00068 typedef uint32_t _width_type;
00069 uint32_t width;
00070
00071 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _distortion_model_type;
00072 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > distortion_model;
00073
00074 typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > _D_type;
00075 std::vector<double, typename ContainerAllocator::template rebind<double>::other > D;
00076
00077 typedef boost::array<double, 9> _K_type;
00078 boost::array<double, 9> K;
00079
00080 typedef boost::array<double, 9> _R_type;
00081 boost::array<double, 9> R;
00082
00083 typedef boost::array<double, 12> _P_type;
00084 boost::array<double, 12> P;
00085
00086 typedef uint32_t _binning_x_type;
00087 uint32_t binning_x;
00088
00089 typedef uint32_t _binning_y_type;
00090 uint32_t binning_y;
00091
00092 typedef ::sensor_msgs::RegionOfInterest_<ContainerAllocator> _roi_type;
00093 ::sensor_msgs::RegionOfInterest_<ContainerAllocator> roi;
00094
00095
00096 ROS_DEPRECATED uint32_t get_D_size() const { return (uint32_t)D.size(); }
00097 ROS_DEPRECATED void set_D_size(uint32_t size) { D.resize((size_t)size); }
00098 ROS_DEPRECATED void get_D_vec(std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) const { vec = this->D; }
00099 ROS_DEPRECATED void set_D_vec(const std::vector<double, typename ContainerAllocator::template rebind<double>::other > & vec) { this->D = vec; }
00100 ROS_DEPRECATED uint32_t get_K_size() const { return (uint32_t)K.size(); }
00101 ROS_DEPRECATED uint32_t get_R_size() const { return (uint32_t)R.size(); }
00102 ROS_DEPRECATED uint32_t get_P_size() const { return (uint32_t)P.size(); }
00103 private:
00104 static const char* __s_getDataType_() { return "sensor_msgs/CameraInfo"; }
00105 public:
00106 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00107
00108 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00109
00110 private:
00111 static const char* __s_getMD5Sum_() { return "c9a58c1b0b154e0e6da7578cb991d214"; }
00112 public:
00113 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00114
00115 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00116
00117 private:
00118 static const char* __s_getMessageDefinition_() { return "# This message defines meta information for a camera. It should be in a\n\
00119 # camera namespace on topic \"camera_info\" and accompanied by up to five\n\
00120 # image topics named:\n\
00121 #\n\
00122 # image_raw - raw data from the camera driver, possibly Bayer encoded\n\
00123 # image - monochrome, distorted\n\
00124 # image_color - color, distorted\n\
00125 # image_rect - monochrome, rectified\n\
00126 # image_rect_color - color, rectified\n\
00127 #\n\
00128 # The image_pipeline contains packages (image_proc, stereo_image_proc)\n\
00129 # for producing the four processed image topics from image_raw and\n\
00130 # camera_info. The meaning of the camera parameters are described in\n\
00131 # detail at http://www.ros.org/wiki/image_pipeline/CameraInfo.\n\
00132 #\n\
00133 # The image_geometry package provides a user-friendly interface to\n\
00134 # common operations using this meta information. If you want to, e.g.,\n\
00135 # project a 3d point into image coordinates, we strongly recommend\n\
00136 # using image_geometry.\n\
00137 #\n\
00138 # If the camera is uncalibrated, the matrices D, K, R, P should be left\n\
00139 # zeroed out. In particular, clients may assume that K[0] == 0.0\n\
00140 # indicates an uncalibrated camera.\n\
00141 \n\
00142 #######################################################################\n\
00143 # Image acquisition info #\n\
00144 #######################################################################\n\
00145 \n\
00146 # Time of image acquisition, camera coordinate frame ID\n\
00147 Header header # Header timestamp should be acquisition time of image\n\
00148 # Header frame_id should be optical frame of camera\n\
00149 # origin of frame should be optical center of camera\n\
00150 # +x should point to the right in the image\n\
00151 # +y should point down in the image\n\
00152 # +z should point into the plane of the image\n\
00153 \n\
00154 \n\
00155 #######################################################################\n\
00156 # Calibration Parameters #\n\
00157 #######################################################################\n\
00158 # These are fixed during camera calibration. Their values will be the #\n\
00159 # same in all messages until the camera is recalibrated. Note that #\n\
00160 # self-calibrating systems may \"recalibrate\" frequently. #\n\
00161 # #\n\
00162 # The internal parameters can be used to warp a raw (distorted) image #\n\
00163 # to: #\n\
00164 # 1. An undistorted image (requires D and K) #\n\
00165 # 2. A rectified image (requires D, K, R) #\n\
00166 # The projection matrix P projects 3D points into the rectified image.#\n\
00167 #######################################################################\n\
00168 \n\
00169 # The image dimensions with which the camera was calibrated. Normally\n\
00170 # this will be the full camera resolution in pixels.\n\
00171 uint32 height\n\
00172 uint32 width\n\
00173 \n\
00174 # The distortion model used. Supported models are listed in\n\
00175 # sensor_msgs/distortion_models.h. For most cameras, \"plumb_bob\" - a\n\
00176 # simple model of radial and tangential distortion - is sufficent.\n\
00177 string distortion_model\n\
00178 \n\
00179 # The distortion parameters, size depending on the distortion model.\n\
00180 # For \"plumb_bob\", the 5 parameters are: (k1, k2, t1, t2, k3).\n\
00181 float64[] D\n\
00182 \n\
00183 # Intrinsic camera matrix for the raw (distorted) images.\n\
00184 # [fx 0 cx]\n\
00185 # K = [ 0 fy cy]\n\
00186 # [ 0 0 1]\n\
00187 # Projects 3D points in the camera coordinate frame to 2D pixel\n\
00188 # coordinates using the focal lengths (fx, fy) and principal point\n\
00189 # (cx, cy).\n\
00190 float64[9] K # 3x3 row-major matrix\n\
00191 \n\
00192 # Rectification matrix (stereo cameras only)\n\
00193 # A rotation matrix aligning the camera coordinate system to the ideal\n\
00194 # stereo image plane so that epipolar lines in both stereo images are\n\
00195 # parallel.\n\
00196 float64[9] R # 3x3 row-major matrix\n\
00197 \n\
00198 # Projection/camera matrix\n\
00199 # [fx' 0 cx' Tx]\n\
00200 # P = [ 0 fy' cy' Ty]\n\
00201 # [ 0 0 1 0]\n\
00202 # By convention, this matrix specifies the intrinsic (camera) matrix\n\
00203 # of the processed (rectified) image. That is, the left 3x3 portion\n\
00204 # is the normal camera intrinsic matrix for the rectified image.\n\
00205 # It projects 3D points in the camera coordinate frame to 2D pixel\n\
00206 # coordinates using the focal lengths (fx', fy') and principal point\n\
00207 # (cx', cy') - these may differ from the values in K.\n\
00208 # For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will\n\
00209 # also have R = the identity and P[1:3,1:3] = K.\n\
00210 # For a stereo pair, the fourth column [Tx Ty 0]' is related to the\n\
00211 # position of the optical center of the second camera in the first\n\
00212 # camera's frame. We assume Tz = 0 so both cameras are in the same\n\
00213 # stereo image plane. The first camera always has Tx = Ty = 0. For\n\
00214 # the right (second) camera of a horizontal stereo pair, Ty = 0 and\n\
00215 # Tx = -fx' * B, where B is the baseline between the cameras.\n\
00216 # Given a 3D point [X Y Z]', the projection (x, y) of the point onto\n\
00217 # the rectified image is given by:\n\
00218 # [u v w]' = P * [X Y Z 1]'\n\
00219 # x = u / w\n\
00220 # y = v / w\n\
00221 # This holds for both images of a stereo pair.\n\
00222 float64[12] P # 3x4 row-major matrix\n\
00223 \n\
00224 \n\
00225 #######################################################################\n\
00226 # Operational Parameters #\n\
00227 #######################################################################\n\
00228 # These define the image region actually captured by the camera #\n\
00229 # driver. Although they affect the geometry of the output image, they #\n\
00230 # may be changed freely without recalibrating the camera. #\n\
00231 #######################################################################\n\
00232 \n\
00233 # Binning refers here to any camera setting which combines rectangular\n\
00234 # neighborhoods of pixels into larger \"super-pixels.\" It reduces the\n\
00235 # resolution of the output image to\n\
00236 # (width / binning_x) x (height / binning_y).\n\
00237 # The default values binning_x = binning_y = 0 is considered the same\n\
00238 # as binning_x = binning_y = 1 (no subsampling).\n\
00239 uint32 binning_x\n\
00240 uint32 binning_y\n\
00241 \n\
00242 # Region of interest (subwindow of full camera resolution), given in\n\
00243 # full resolution (unbinned) image coordinates. A particular ROI\n\
00244 # always denotes the same window of pixels on the camera sensor,\n\
00245 # regardless of binning settings.\n\
00246 # The default setting of roi (all values 0) is considered the same as\n\
00247 # full resolution (roi.width = width, roi.height = height).\n\
00248 RegionOfInterest roi\n\
00249 \n\
00250 ================================================================================\n\
00251 MSG: std_msgs/Header\n\
00252 # Standard metadata for higher-level stamped data types.\n\
00253 # This is generally used to communicate timestamped data \n\
00254 # in a particular coordinate frame.\n\
00255 # \n\
00256 # sequence ID: consecutively increasing ID \n\
00257 uint32 seq\n\
00258 #Two-integer timestamp that is expressed as:\n\
00259 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00260 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00261 # time-handling sugar is provided by the client library\n\
00262 time stamp\n\
00263 #Frame this data is associated with\n\
00264 # 0: no frame\n\
00265 # 1: global frame\n\
00266 string frame_id\n\
00267 \n\
00268 ================================================================================\n\
00269 MSG: sensor_msgs/RegionOfInterest\n\
00270 # This message is used to specify a region of interest within an image.\n\
00271 #\n\
00272 # When used to specify the ROI setting of the camera when the image was\n\
00273 # taken, the height and width fields should either match the height and\n\
00274 # width fields for the associated image; or height = width = 0\n\
00275 # indicates that the full resolution image was captured.\n\
00276 \n\
00277 uint32 x_offset # Leftmost pixel of the ROI\n\
00278 # (0 if the ROI includes the left edge of the image)\n\
00279 uint32 y_offset # Topmost pixel of the ROI\n\
00280 # (0 if the ROI includes the top edge of the image)\n\
00281 uint32 height # Height of ROI\n\
00282 uint32 width # Width of ROI\n\
00283 \n\
00284 # True if a distinct rectified ROI should be calculated from the \"raw\"\n\
00285 # ROI in this message. Typically this should be False if the full image\n\
00286 # is captured (ROI not used), and True if a subwindow is captured (ROI\n\
00287 # used).\n\
00288 bool do_rectify\n\
00289 \n\
00290 "; }
00291 public:
00292 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00293
00294 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00295
00296 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00297 {
00298 ros::serialization::OStream stream(write_ptr, 1000000000);
00299 ros::serialization::serialize(stream, header);
00300 ros::serialization::serialize(stream, height);
00301 ros::serialization::serialize(stream, width);
00302 ros::serialization::serialize(stream, distortion_model);
00303 ros::serialization::serialize(stream, D);
00304 ros::serialization::serialize(stream, K);
00305 ros::serialization::serialize(stream, R);
00306 ros::serialization::serialize(stream, P);
00307 ros::serialization::serialize(stream, binning_x);
00308 ros::serialization::serialize(stream, binning_y);
00309 ros::serialization::serialize(stream, roi);
00310 return stream.getData();
00311 }
00312
00313 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00314 {
00315 ros::serialization::IStream stream(read_ptr, 1000000000);
00316 ros::serialization::deserialize(stream, header);
00317 ros::serialization::deserialize(stream, height);
00318 ros::serialization::deserialize(stream, width);
00319 ros::serialization::deserialize(stream, distortion_model);
00320 ros::serialization::deserialize(stream, D);
00321 ros::serialization::deserialize(stream, K);
00322 ros::serialization::deserialize(stream, R);
00323 ros::serialization::deserialize(stream, P);
00324 ros::serialization::deserialize(stream, binning_x);
00325 ros::serialization::deserialize(stream, binning_y);
00326 ros::serialization::deserialize(stream, roi);
00327 return stream.getData();
00328 }
00329
00330 ROS_DEPRECATED virtual uint32_t serializationLength() const
00331 {
00332 uint32_t size = 0;
00333 size += ros::serialization::serializationLength(header);
00334 size += ros::serialization::serializationLength(height);
00335 size += ros::serialization::serializationLength(width);
00336 size += ros::serialization::serializationLength(distortion_model);
00337 size += ros::serialization::serializationLength(D);
00338 size += ros::serialization::serializationLength(K);
00339 size += ros::serialization::serializationLength(R);
00340 size += ros::serialization::serializationLength(P);
00341 size += ros::serialization::serializationLength(binning_x);
00342 size += ros::serialization::serializationLength(binning_y);
00343 size += ros::serialization::serializationLength(roi);
00344 return size;
00345 }
00346
00347 typedef boost::shared_ptr< ::sensor_msgs::CameraInfo_<ContainerAllocator> > Ptr;
00348 typedef boost::shared_ptr< ::sensor_msgs::CameraInfo_<ContainerAllocator> const> ConstPtr;
00349 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00350 };
00351 typedef ::sensor_msgs::CameraInfo_<std::allocator<void> > CameraInfo;
00352
00353 typedef boost::shared_ptr< ::sensor_msgs::CameraInfo> CameraInfoPtr;
00354 typedef boost::shared_ptr< ::sensor_msgs::CameraInfo const> CameraInfoConstPtr;
00355
00356
00357 template<typename ContainerAllocator>
00358 std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::CameraInfo_<ContainerAllocator> & v)
00359 {
00360 ros::message_operations::Printer< ::sensor_msgs::CameraInfo_<ContainerAllocator> >::stream(s, "", v);
00361 return s;}
00362
00363 }
00364
00365 namespace ros
00366 {
00367 namespace message_traits
00368 {
00369 template<class ContainerAllocator> struct IsMessage< ::sensor_msgs::CameraInfo_<ContainerAllocator> > : public TrueType {};
00370 template<class ContainerAllocator> struct IsMessage< ::sensor_msgs::CameraInfo_<ContainerAllocator> const> : public TrueType {};
00371 template<class ContainerAllocator>
00372 struct MD5Sum< ::sensor_msgs::CameraInfo_<ContainerAllocator> > {
00373 static const char* value()
00374 {
00375 return "c9a58c1b0b154e0e6da7578cb991d214";
00376 }
00377
00378 static const char* value(const ::sensor_msgs::CameraInfo_<ContainerAllocator> &) { return value(); }
00379 static const uint64_t static_value1 = 0xc9a58c1b0b154e0eULL;
00380 static const uint64_t static_value2 = 0x6da7578cb991d214ULL;
00381 };
00382
00383 template<class ContainerAllocator>
00384 struct DataType< ::sensor_msgs::CameraInfo_<ContainerAllocator> > {
00385 static const char* value()
00386 {
00387 return "sensor_msgs/CameraInfo";
00388 }
00389
00390 static const char* value(const ::sensor_msgs::CameraInfo_<ContainerAllocator> &) { return value(); }
00391 };
00392
00393 template<class ContainerAllocator>
00394 struct Definition< ::sensor_msgs::CameraInfo_<ContainerAllocator> > {
00395 static const char* value()
00396 {
00397 return "# This message defines meta information for a camera. It should be in a\n\
00398 # camera namespace on topic \"camera_info\" and accompanied by up to five\n\
00399 # image topics named:\n\
00400 #\n\
00401 # image_raw - raw data from the camera driver, possibly Bayer encoded\n\
00402 # image - monochrome, distorted\n\
00403 # image_color - color, distorted\n\
00404 # image_rect - monochrome, rectified\n\
00405 # image_rect_color - color, rectified\n\
00406 #\n\
00407 # The image_pipeline contains packages (image_proc, stereo_image_proc)\n\
00408 # for producing the four processed image topics from image_raw and\n\
00409 # camera_info. The meaning of the camera parameters are described in\n\
00410 # detail at http://www.ros.org/wiki/image_pipeline/CameraInfo.\n\
00411 #\n\
00412 # The image_geometry package provides a user-friendly interface to\n\
00413 # common operations using this meta information. If you want to, e.g.,\n\
00414 # project a 3d point into image coordinates, we strongly recommend\n\
00415 # using image_geometry.\n\
00416 #\n\
00417 # If the camera is uncalibrated, the matrices D, K, R, P should be left\n\
00418 # zeroed out. In particular, clients may assume that K[0] == 0.0\n\
00419 # indicates an uncalibrated camera.\n\
00420 \n\
00421 #######################################################################\n\
00422 # Image acquisition info #\n\
00423 #######################################################################\n\
00424 \n\
00425 # Time of image acquisition, camera coordinate frame ID\n\
00426 Header header # Header timestamp should be acquisition time of image\n\
00427 # Header frame_id should be optical frame of camera\n\
00428 # origin of frame should be optical center of camera\n\
00429 # +x should point to the right in the image\n\
00430 # +y should point down in the image\n\
00431 # +z should point into the plane of the image\n\
00432 \n\
00433 \n\
00434 #######################################################################\n\
00435 # Calibration Parameters #\n\
00436 #######################################################################\n\
00437 # These are fixed during camera calibration. Their values will be the #\n\
00438 # same in all messages until the camera is recalibrated. Note that #\n\
00439 # self-calibrating systems may \"recalibrate\" frequently. #\n\
00440 # #\n\
00441 # The internal parameters can be used to warp a raw (distorted) image #\n\
00442 # to: #\n\
00443 # 1. An undistorted image (requires D and K) #\n\
00444 # 2. A rectified image (requires D, K, R) #\n\
00445 # The projection matrix P projects 3D points into the rectified image.#\n\
00446 #######################################################################\n\
00447 \n\
00448 # The image dimensions with which the camera was calibrated. Normally\n\
00449 # this will be the full camera resolution in pixels.\n\
00450 uint32 height\n\
00451 uint32 width\n\
00452 \n\
00453 # The distortion model used. Supported models are listed in\n\
00454 # sensor_msgs/distortion_models.h. For most cameras, \"plumb_bob\" - a\n\
00455 # simple model of radial and tangential distortion - is sufficent.\n\
00456 string distortion_model\n\
00457 \n\
00458 # The distortion parameters, size depending on the distortion model.\n\
00459 # For \"plumb_bob\", the 5 parameters are: (k1, k2, t1, t2, k3).\n\
00460 float64[] D\n\
00461 \n\
00462 # Intrinsic camera matrix for the raw (distorted) images.\n\
00463 # [fx 0 cx]\n\
00464 # K = [ 0 fy cy]\n\
00465 # [ 0 0 1]\n\
00466 # Projects 3D points in the camera coordinate frame to 2D pixel\n\
00467 # coordinates using the focal lengths (fx, fy) and principal point\n\
00468 # (cx, cy).\n\
00469 float64[9] K # 3x3 row-major matrix\n\
00470 \n\
00471 # Rectification matrix (stereo cameras only)\n\
00472 # A rotation matrix aligning the camera coordinate system to the ideal\n\
00473 # stereo image plane so that epipolar lines in both stereo images are\n\
00474 # parallel.\n\
00475 float64[9] R # 3x3 row-major matrix\n\
00476 \n\
00477 # Projection/camera matrix\n\
00478 # [fx' 0 cx' Tx]\n\
00479 # P = [ 0 fy' cy' Ty]\n\
00480 # [ 0 0 1 0]\n\
00481 # By convention, this matrix specifies the intrinsic (camera) matrix\n\
00482 # of the processed (rectified) image. That is, the left 3x3 portion\n\
00483 # is the normal camera intrinsic matrix for the rectified image.\n\
00484 # It projects 3D points in the camera coordinate frame to 2D pixel\n\
00485 # coordinates using the focal lengths (fx', fy') and principal point\n\
00486 # (cx', cy') - these may differ from the values in K.\n\
00487 # For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will\n\
00488 # also have R = the identity and P[1:3,1:3] = K.\n\
00489 # For a stereo pair, the fourth column [Tx Ty 0]' is related to the\n\
00490 # position of the optical center of the second camera in the first\n\
00491 # camera's frame. We assume Tz = 0 so both cameras are in the same\n\
00492 # stereo image plane. The first camera always has Tx = Ty = 0. For\n\
00493 # the right (second) camera of a horizontal stereo pair, Ty = 0 and\n\
00494 # Tx = -fx' * B, where B is the baseline between the cameras.\n\
00495 # Given a 3D point [X Y Z]', the projection (x, y) of the point onto\n\
00496 # the rectified image is given by:\n\
00497 # [u v w]' = P * [X Y Z 1]'\n\
00498 # x = u / w\n\
00499 # y = v / w\n\
00500 # This holds for both images of a stereo pair.\n\
00501 float64[12] P # 3x4 row-major matrix\n\
00502 \n\
00503 \n\
00504 #######################################################################\n\
00505 # Operational Parameters #\n\
00506 #######################################################################\n\
00507 # These define the image region actually captured by the camera #\n\
00508 # driver. Although they affect the geometry of the output image, they #\n\
00509 # may be changed freely without recalibrating the camera. #\n\
00510 #######################################################################\n\
00511 \n\
00512 # Binning refers here to any camera setting which combines rectangular\n\
00513 # neighborhoods of pixels into larger \"super-pixels.\" It reduces the\n\
00514 # resolution of the output image to\n\
00515 # (width / binning_x) x (height / binning_y).\n\
00516 # The default values binning_x = binning_y = 0 is considered the same\n\
00517 # as binning_x = binning_y = 1 (no subsampling).\n\
00518 uint32 binning_x\n\
00519 uint32 binning_y\n\
00520 \n\
00521 # Region of interest (subwindow of full camera resolution), given in\n\
00522 # full resolution (unbinned) image coordinates. A particular ROI\n\
00523 # always denotes the same window of pixels on the camera sensor,\n\
00524 # regardless of binning settings.\n\
00525 # The default setting of roi (all values 0) is considered the same as\n\
00526 # full resolution (roi.width = width, roi.height = height).\n\
00527 RegionOfInterest roi\n\
00528 \n\
00529 ================================================================================\n\
00530 MSG: std_msgs/Header\n\
00531 # Standard metadata for higher-level stamped data types.\n\
00532 # This is generally used to communicate timestamped data \n\
00533 # in a particular coordinate frame.\n\
00534 # \n\
00535 # sequence ID: consecutively increasing ID \n\
00536 uint32 seq\n\
00537 #Two-integer timestamp that is expressed as:\n\
00538 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00539 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00540 # time-handling sugar is provided by the client library\n\
00541 time stamp\n\
00542 #Frame this data is associated with\n\
00543 # 0: no frame\n\
00544 # 1: global frame\n\
00545 string frame_id\n\
00546 \n\
00547 ================================================================================\n\
00548 MSG: sensor_msgs/RegionOfInterest\n\
00549 # This message is used to specify a region of interest within an image.\n\
00550 #\n\
00551 # When used to specify the ROI setting of the camera when the image was\n\
00552 # taken, the height and width fields should either match the height and\n\
00553 # width fields for the associated image; or height = width = 0\n\
00554 # indicates that the full resolution image was captured.\n\
00555 \n\
00556 uint32 x_offset # Leftmost pixel of the ROI\n\
00557 # (0 if the ROI includes the left edge of the image)\n\
00558 uint32 y_offset # Topmost pixel of the ROI\n\
00559 # (0 if the ROI includes the top edge of the image)\n\
00560 uint32 height # Height of ROI\n\
00561 uint32 width # Width of ROI\n\
00562 \n\
00563 # True if a distinct rectified ROI should be calculated from the \"raw\"\n\
00564 # ROI in this message. Typically this should be False if the full image\n\
00565 # is captured (ROI not used), and True if a subwindow is captured (ROI\n\
00566 # used).\n\
00567 bool do_rectify\n\
00568 \n\
00569 ";
00570 }
00571
00572 static const char* value(const ::sensor_msgs::CameraInfo_<ContainerAllocator> &) { return value(); }
00573 };
00574
00575 template<class ContainerAllocator> struct HasHeader< ::sensor_msgs::CameraInfo_<ContainerAllocator> > : public TrueType {};
00576 template<class ContainerAllocator> struct HasHeader< const ::sensor_msgs::CameraInfo_<ContainerAllocator> > : public TrueType {};
00577 }
00578 }
00579
00580 namespace ros
00581 {
00582 namespace serialization
00583 {
00584
00585 template<class ContainerAllocator> struct Serializer< ::sensor_msgs::CameraInfo_<ContainerAllocator> >
00586 {
00587 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00588 {
00589 stream.next(m.header);
00590 stream.next(m.height);
00591 stream.next(m.width);
00592 stream.next(m.distortion_model);
00593 stream.next(m.D);
00594 stream.next(m.K);
00595 stream.next(m.R);
00596 stream.next(m.P);
00597 stream.next(m.binning_x);
00598 stream.next(m.binning_y);
00599 stream.next(m.roi);
00600 }
00601
00602 ROS_DECLARE_ALLINONE_SERIALIZER;
00603 };
00604 }
00605 }
00606
00607 namespace ros
00608 {
00609 namespace message_operations
00610 {
00611
00612 template<class ContainerAllocator>
00613 struct Printer< ::sensor_msgs::CameraInfo_<ContainerAllocator> >
00614 {
00615 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::CameraInfo_<ContainerAllocator> & v)
00616 {
00617 s << indent << "header: ";
00618 s << std::endl;
00619 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
00620 s << indent << "height: ";
00621 Printer<uint32_t>::stream(s, indent + " ", v.height);
00622 s << indent << "width: ";
00623 Printer<uint32_t>::stream(s, indent + " ", v.width);
00624 s << indent << "distortion_model: ";
00625 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.distortion_model);
00626 s << indent << "D[]" << std::endl;
00627 for (size_t i = 0; i < v.D.size(); ++i)
00628 {
00629 s << indent << " D[" << i << "]: ";
00630 Printer<double>::stream(s, indent + " ", v.D[i]);
00631 }
00632 s << indent << "K[]" << std::endl;
00633 for (size_t i = 0; i < v.K.size(); ++i)
00634 {
00635 s << indent << " K[" << i << "]: ";
00636 Printer<double>::stream(s, indent + " ", v.K[i]);
00637 }
00638 s << indent << "R[]" << std::endl;
00639 for (size_t i = 0; i < v.R.size(); ++i)
00640 {
00641 s << indent << " R[" << i << "]: ";
00642 Printer<double>::stream(s, indent + " ", v.R[i]);
00643 }
00644 s << indent << "P[]" << std::endl;
00645 for (size_t i = 0; i < v.P.size(); ++i)
00646 {
00647 s << indent << " P[" << i << "]: ";
00648 Printer<double>::stream(s, indent + " ", v.P[i]);
00649 }
00650 s << indent << "binning_x: ";
00651 Printer<uint32_t>::stream(s, indent + " ", v.binning_x);
00652 s << indent << "binning_y: ";
00653 Printer<uint32_t>::stream(s, indent + " ", v.binning_y);
00654 s << indent << "roi: ";
00655 s << std::endl;
00656 Printer< ::sensor_msgs::RegionOfInterest_<ContainerAllocator> >::stream(s, indent + " ", v.roi);
00657 }
00658 };
00659
00660
00661 }
00662 }
00663
00664 #endif // SENSOR_MSGS_MESSAGE_CAMERAINFO_H
00665