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