143 #ifndef YARP_ROSMSG_sensor_msgs_CameraInfo_h
144 #define YARP_ROSMSG_sensor_msgs_CameraInfo_h
165 std::vector<yarp::conf::float64_t>
D;
166 std::vector<yarp::conf::float64_t>
K;
167 std::vector<yarp::conf::float64_t>
R;
168 std::vector<yarp::conf::float64_t>
P;
322 for (
int i=0; i<len; i++) {
332 for (
int i=0; i<len; i++) {
342 for (
int i=0; i<len; i++) {
352 for (
int i=0; i<len; i++) {
455 for (
size_t i=0; i<
D.size(); i++) {
462 for (
size_t i=0; i<
K.size(); i++) {
469 for (
size_t i=0; i<
R.size(); i++) {
476 for (
size_t i=0; i<
P.size(); i++) {
510 static constexpr
const char*
typeName =
"sensor_msgs/CameraInfo";
513 static constexpr
const char*
typeChecksum =
"c9a58c1b0b154e0e6da7578cb991d214";
517 # This message defines meta information for a camera. It should be in a\n\
518 # camera namespace on topic \"camera_info\" and accompanied by up to five\n\
519 # image topics named:\n\
521 # image_raw - raw data from the camera driver, possibly Bayer encoded\n\
522 # image - monochrome, distorted\n\
523 # image_color - color, distorted\n\
524 # image_rect - monochrome, rectified\n\
525 # image_rect_color - color, rectified\n\
527 # The image_pipeline contains packages (image_proc, stereo_image_proc)\n\
528 # for producing the four processed image topics from image_raw and\n\
529 # camera_info. The meaning of the camera parameters are described in\n\
530 # detail at http://www.ros.org/wiki/image_pipeline/CameraInfo.\n\
532 # The image_geometry package provides a user-friendly interface to\n\
533 # common operations using this meta information. If you want to, e.g.,\n\
534 # project a 3d point into image coordinates, we strongly recommend\n\
535 # using image_geometry.\n\
537 # If the camera is uncalibrated, the matrices D, K, R, P should be left\n\
538 # zeroed out. In particular, clients may assume that K[0] == 0.0\n\
539 # indicates an uncalibrated camera.\n\
541 #######################################################################\n\
542 # Image acquisition info #\n\
543 #######################################################################\n\
545 # Time of image acquisition, camera coordinate frame ID\n\
546 Header header # Header timestamp should be acquisition time of image\n\
547 # Header frame_id should be optical frame of camera\n\
548 # origin of frame should be optical center of camera\n\
549 # +x should point to the right in the image\n\
550 # +y should point down in the image\n\
551 # +z should point into the plane of the image\n\
554 #######################################################################\n\
555 # Calibration Parameters #\n\
556 #######################################################################\n\
557 # These are fixed during camera calibration. Their values will be the #\n\
558 # same in all messages until the camera is recalibrated. Note that #\n\
559 # self-calibrating systems may \"recalibrate\" frequently. #\n\
561 # The internal parameters can be used to warp a raw (distorted) image #\n\
563 # 1. An undistorted image (requires D and K) #\n\
564 # 2. A rectified image (requires D, K, R) #\n\
565 # The projection matrix P projects 3D points into the rectified image.#\n\
566 #######################################################################\n\
568 # The image dimensions with which the camera was calibrated. Normally\n\
569 # this will be the full camera resolution in pixels.\n\
573 # The distortion model used. Supported models are listed in\n\
574 # sensor_msgs/distortion_models.h. For most cameras, \"plumb_bob\" - a\n\
575 # simple model of radial and tangential distortion - is sufficient.\n\
576 string distortion_model\n\
578 # The distortion parameters, size depending on the distortion model.\n\
579 # For \"plumb_bob\", the 5 parameters are: (k1, k2, t1, t2, k3).\n\
582 # Intrinsic camera matrix for the raw (distorted) images.\n\
586 # Projects 3D points in the camera coordinate frame to 2D pixel\n\
587 # coordinates using the focal lengths (fx, fy) and principal point\n\
589 float64[9] K # 3x3 row-major matrix\n\
591 # Rectification matrix (stereo cameras only)\n\
592 # A rotation matrix aligning the camera coordinate system to the ideal\n\
593 # stereo image plane so that epipolar lines in both stereo images are\n\
595 float64[9] R # 3x3 row-major matrix\n\
597 # Projection/camera matrix\n\
599 # P = [ 0 fy' cy' Ty]\n\
601 # By convention, this matrix specifies the intrinsic (camera) matrix\n\
602 # of the processed (rectified) image. That is, the left 3x3 portion\n\
603 # is the normal camera intrinsic matrix for the rectified image.\n\
604 # It projects 3D points in the camera coordinate frame to 2D pixel\n\
605 # coordinates using the focal lengths (fx', fy') and principal point\n\
606 # (cx', cy') - these may differ from the values in K.\n\
607 # For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will\n\
608 # also have R = the identity and P[1:3,1:3] = K.\n\
609 # For a stereo pair, the fourth column [Tx Ty 0]' is related to the\n\
610 # position of the optical center of the second camera in the first\n\
611 # camera's frame. We assume Tz = 0 so both cameras are in the same\n\
612 # stereo image plane. The first camera always has Tx = Ty = 0. For\n\
613 # the right (second) camera of a horizontal stereo pair, Ty = 0 and\n\
614 # Tx = -fx' * B, where B is the baseline between the cameras.\n\
615 # Given a 3D point [X Y Z]', the projection (x, y) of the point onto\n\
616 # the rectified image is given by:\n\
617 # [u v w]' = P * [X Y Z 1]'\n\
620 # This holds for both images of a stereo pair.\n\
621 float64[12] P # 3x4 row-major matrix\n\
624 #######################################################################\n\
625 # Operational Parameters #\n\
626 #######################################################################\n\
627 # These define the image region actually captured by the camera #\n\
628 # driver. Although they affect the geometry of the output image, they #\n\
629 # may be changed freely without recalibrating the camera. #\n\
630 #######################################################################\n\
632 # Binning refers here to any camera setting which combines rectangular\n\
633 # neighborhoods of pixels into larger \"super-pixels.\" It reduces the\n\
634 # resolution of the output image to\n\
635 # (width / binning_x) x (height / binning_y).\n\
636 # The default values binning_x = binning_y = 0 is considered the same\n\
637 # as binning_x = binning_y = 1 (no subsampling).\n\
641 # Region of interest (subwindow of full camera resolution), given in\n\
642 # full resolution (unbinned) image coordinates. A particular ROI\n\
643 # always denotes the same window of pixels on the camera sensor,\n\
644 # regardless of binning settings.\n\
645 # The default setting of roi (all values 0) is considered the same as\n\
646 # full resolution (roi.width = width, roi.height = height).\n\
647 RegionOfInterest roi\n\
649 ================================================================================\n\
650 MSG: std_msgs/Header\n\
651 # Standard metadata for higher-level stamped data types.\n\
652 # This is generally used to communicate timestamped data \n\
653 # in a particular coordinate frame.\n\
655 # sequence ID: consecutively increasing ID \n\
657 #Two-integer timestamp that is expressed as:\n\
658 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
659 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
660 # time-handling sugar is provided by the client library\n\
662 #Frame this data is associated with\n\
667 ================================================================================\n\
668 MSG: sensor_msgs/RegionOfInterest\n\
669 # This message is used to specify a region of interest within an image.\n\
671 # When used to specify the ROI setting of the camera when the image was\n\
672 # taken, the height and width fields should either match the height and\n\
673 # width fields for the associated image; or height = width = 0\n\
674 # indicates that the full resolution image was captured.\n\
676 uint32 x_offset # Leftmost pixel of the ROI\n\
677 # (0 if the ROI includes the left edge of the image)\n\
678 uint32 y_offset # Topmost pixel of the ROI\n\
679 # (0 if the ROI includes the top edge of the image)\n\
680 uint32 height # Height of ROI\n\
681 uint32 width # Width of ROI\n\
683 # True if a distinct rectified ROI should be calculated from the \"raw\"\n\
684 # ROI in this message. Typically this should be False if the full image\n\
685 # is captured (ROI not used), and True if a subwindow is captured (ROI\n\
#define BOTTLE_TAG_FLOAT64
#define BOTTLE_TAG_STRING
An interface for reading from a network connection.
virtual bool expectBlock(char *data, size_t len)=0
Read a block of data from the network connection.
virtual bool isBareMode() const =0
Check if the connection is bare mode.
virtual std::int32_t expectInt32()=0
Read a 32-bit integer from the network connection.
virtual bool convertTextMode()=0
Reads in a standard description in text mode, and converts it to a standard description in binary.
virtual bool isError() const =0
virtual yarp::conf::float64_t expectFloat64()=0
Read a 64-bit floating point number from the network connection.
An interface for writing to a network connection.
virtual bool isError() const =0
virtual bool isBareMode() const =0
Check if the connection is bare mode.
virtual void appendExternalBlock(const char *data, size_t len)=0
Send a block of data to the network connection, without making a copy.
virtual bool convertTextMode()=0
Converts a standard description in binary into a textual description, if the connection is in text-mo...
virtual void appendInt32(std::int32_t data)=0
Send a representation of a 32-bit integer to the network connection.
virtual void appendFloat64(yarp::conf::float64_t data)=0
Send a representation of a 64-bit floating point number to the network connection.
static Type byName(const char *name)
Type & addProperty(const char *key, const Value &val)
A single value (typically within a Bottle).
A "tamed" Portable, that promises to serialize itself in an IDL-friendly way.
virtual bool read(yarp::os::idl::WireReader &reader)
virtual bool write(const yarp::os::idl::WireWriter &writer) const
IDL-friendly connection reader.
bool readString(std::string &str, bool *is_vocab=nullptr)
std::int32_t expectInt32()
std::string distortion_model
std::vector< yarp::conf::float64_t > R
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
static constexpr const char * typeText
static constexpr const char * typeChecksum
std::vector< yarp::conf::float64_t > K
yarp::rosmsg::sensor_msgs::RegionOfInterest roi
std::vector< yarp::conf::float64_t > P
bool readBare(yarp::os::ConnectionReader &connection) override
yarp::os::idl::BareStyle< yarp::rosmsg::sensor_msgs::CameraInfo > rosStyle
yarp::os::idl::BottleStyle< yarp::rosmsg::sensor_msgs::CameraInfo > bottleStyle
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
yarp::rosmsg::std_msgs::Header header
std::vector< yarp::conf::float64_t > D
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
static constexpr const char * typeName
bool writeBare(yarp::os::ConnectionWriter &connection) const override
yarp::os::Type getType() const override
bool readBottle(yarp::os::ConnectionReader &connection) override
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
The main, catch-all namespace for YARP.