00001
00002
00003 package ros.pkg.sensor_msgs.msg;
00004
00005 import java.nio.ByteBuffer;
00006
00007 public class CameraInfo extends ros.communication.Message {
00008
00009 public ros.pkg.std_msgs.msg.Header header = new ros.pkg.std_msgs.msg.Header();
00010 public long height;
00011 public long width;
00012 public java.lang.String distortion_model = new java.lang.String();
00013 public double[] D = new double[0];
00014 public double[] K = new double[9];
00015 public double[] R = new double[9];
00016 public double[] P = new double[12];
00017 public long binning_x;
00018 public long binning_y;
00019 public ros.pkg.sensor_msgs.msg.RegionOfInterest roi = new ros.pkg.sensor_msgs.msg.RegionOfInterest();
00020
00021 public CameraInfo() {
00022 }
00023
00024 public static java.lang.String __s_getDataType() { return "sensor_msgs/CameraInfo"; }
00025 public java.lang.String getDataType() { return __s_getDataType(); }
00026 public static java.lang.String __s_getMD5Sum() { return "c9a58c1b0b154e0e6da7578cb991d214"; }
00027 public java.lang.String getMD5Sum() { return __s_getMD5Sum(); }
00028 public static java.lang.String __s_getMessageDefinition() { return "# This message defines meta information for a camera. It should be in a\n" +
00029 "# camera namespace on topic \"camera_info\" and accompanied by up to five\n" +
00030 "# image topics named:\n" +
00031 "#\n" +
00032 "# image_raw - raw data from the camera driver, possibly Bayer encoded\n" +
00033 "# image - monochrome, distorted\n" +
00034 "# image_color - color, distorted\n" +
00035 "# image_rect - monochrome, rectified\n" +
00036 "# image_rect_color - color, rectified\n" +
00037 "#\n" +
00038 "# The image_pipeline contains packages (image_proc, stereo_image_proc)\n" +
00039 "# for producing the four processed image topics from image_raw and\n" +
00040 "# camera_info. The meaning of the camera parameters are described in\n" +
00041 "# detail at http://www.ros.org/wiki/image_pipeline/CameraInfo.\n" +
00042 "#\n" +
00043 "# The image_geometry package provides a user-friendly interface to\n" +
00044 "# common operations using this meta information. If you want to, e.g.,\n" +
00045 "# project a 3d point into image coordinates, we strongly recommend\n" +
00046 "# using image_geometry.\n" +
00047 "#\n" +
00048 "# If the camera is uncalibrated, the matrices D, K, R, P should be left\n" +
00049 "# zeroed out. In particular, clients may assume that K[0] == 0.0\n" +
00050 "# indicates an uncalibrated camera.\n" +
00051 "\n" +
00052 "#######################################################################\n" +
00053 "# Image acquisition info #\n" +
00054 "#######################################################################\n" +
00055 "\n" +
00056 "# Time of image acquisition, camera coordinate frame ID\n" +
00057 "Header header # Header timestamp should be acquisition time of image\n" +
00058 " # Header frame_id should be optical frame of camera\n" +
00059 " # origin of frame should be optical center of camera\n" +
00060 " # +x should point to the right in the image\n" +
00061 " # +y should point down in the image\n" +
00062 " # +z should point into the plane of the image\n" +
00063 "\n" +
00064 "\n" +
00065 "#######################################################################\n" +
00066 "# Calibration Parameters #\n" +
00067 "#######################################################################\n" +
00068 "# These are fixed during camera calibration. Their values will be the #\n" +
00069 "# same in all messages until the camera is recalibrated. Note that #\n" +
00070 "# self-calibrating systems may \"recalibrate\" frequently. #\n" +
00071 "# #\n" +
00072 "# The internal parameters can be used to warp a raw (distorted) image #\n" +
00073 "# to: #\n" +
00074 "# 1. An undistorted image (requires D and K) #\n" +
00075 "# 2. A rectified image (requires D, K, R) #\n" +
00076 "# The projection matrix P projects 3D points into the rectified image.#\n" +
00077 "#######################################################################\n" +
00078 "\n" +
00079 "# The image dimensions with which the camera was calibrated. Normally\n" +
00080 "# this will be the full camera resolution in pixels.\n" +
00081 "uint32 height\n" +
00082 "uint32 width\n" +
00083 "\n" +
00084 "# The distortion model used. Supported models are listed in\n" +
00085 "# sensor_msgs/distortion_models.h. For most cameras, \"plumb_bob\" - a\n" +
00086 "# simple model of radial and tangential distortion - is sufficent.\n" +
00087 "string distortion_model\n" +
00088 "\n" +
00089 "# The distortion parameters, size depending on the distortion model.\n" +
00090 "# For \"plumb_bob\", the 5 parameters are: (k1, k2, t1, t2, k3).\n" +
00091 "float64[] D\n" +
00092 "\n" +
00093 "# Intrinsic camera matrix for the raw (distorted) images.\n" +
00094 "# [fx 0 cx]\n" +
00095 "# K = [ 0 fy cy]\n" +
00096 "# [ 0 0 1]\n" +
00097 "# Projects 3D points in the camera coordinate frame to 2D pixel\n" +
00098 "# coordinates using the focal lengths (fx, fy) and principal point\n" +
00099 "# (cx, cy).\n" +
00100 "float64[9] K # 3x3 row-major matrix\n" +
00101 "\n" +
00102 "# Rectification matrix (stereo cameras only)\n" +
00103 "# A rotation matrix aligning the camera coordinate system to the ideal\n" +
00104 "# stereo image plane so that epipolar lines in both stereo images are\n" +
00105 "# parallel.\n" +
00106 "float64[9] R # 3x3 row-major matrix\n" +
00107 "\n" +
00108 "# Projection/camera matrix\n" +
00109 "# [fx' 0 cx' Tx]\n" +
00110 "# P = [ 0 fy' cy' Ty]\n" +
00111 "# [ 0 0 1 0]\n" +
00112 "# By convention, this matrix specifies the intrinsic (camera) matrix\n" +
00113 "# of the processed (rectified) image. That is, the left 3x3 portion\n" +
00114 "# is the normal camera intrinsic matrix for the rectified image.\n" +
00115 "# It projects 3D points in the camera coordinate frame to 2D pixel\n" +
00116 "# coordinates using the focal lengths (fx', fy') and principal point\n" +
00117 "# (cx', cy') - these may differ from the values in K.\n" +
00118 "# For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will\n" +
00119 "# also have R = the identity and P[1:3,1:3] = K.\n" +
00120 "# For a stereo pair, the fourth column [Tx Ty 0]' is related to the\n" +
00121 "# position of the optical center of the second camera in the first\n" +
00122 "# camera's frame. We assume Tz = 0 so both cameras are in the same\n" +
00123 "# stereo image plane. The first camera always has Tx = Ty = 0. For\n" +
00124 "# the right (second) camera of a horizontal stereo pair, Ty = 0 and\n" +
00125 "# Tx = -fx' * B, where B is the baseline between the cameras.\n" +
00126 "# Given a 3D point [X Y Z]', the projection (x, y) of the point onto\n" +
00127 "# the rectified image is given by:\n" +
00128 "# [u v w]' = P * [X Y Z 1]'\n" +
00129 "# x = u / w\n" +
00130 "# y = v / w\n" +
00131 "# This holds for both images of a stereo pair.\n" +
00132 "float64[12] P # 3x4 row-major matrix\n" +
00133 "\n" +
00134 "\n" +
00135 "#######################################################################\n" +
00136 "# Operational Parameters #\n" +
00137 "#######################################################################\n" +
00138 "# These define the image region actually captured by the camera #\n" +
00139 "# driver. Although they affect the geometry of the output image, they #\n" +
00140 "# may be changed freely without recalibrating the camera. #\n" +
00141 "#######################################################################\n" +
00142 "\n" +
00143 "# Binning refers here to any camera setting which combines rectangular\n" +
00144 "# neighborhoods of pixels into larger \"super-pixels.\" It reduces the\n" +
00145 "# resolution of the output image to\n" +
00146 "# (width / binning_x) x (height / binning_y).\n" +
00147 "# The default values binning_x = binning_y = 0 is considered the same\n" +
00148 "# as binning_x = binning_y = 1 (no subsampling).\n" +
00149 "uint32 binning_x\n" +
00150 "uint32 binning_y\n" +
00151 "\n" +
00152 "# Region of interest (subwindow of full camera resolution), given in\n" +
00153 "# full resolution (unbinned) image coordinates. A particular ROI\n" +
00154 "# always denotes the same window of pixels on the camera sensor,\n" +
00155 "# regardless of binning settings.\n" +
00156 "# The default setting of roi (all values 0) is considered the same as\n" +
00157 "# full resolution (roi.width = width, roi.height = height).\n" +
00158 "RegionOfInterest roi\n" +
00159 "\n" +
00160 "================================================================================\n" +
00161 "MSG: std_msgs/Header\n" +
00162 "# Standard metadata for higher-level stamped data types.\n" +
00163 "# This is generally used to communicate timestamped data \n" +
00164 "# in a particular coordinate frame.\n" +
00165 "# \n" +
00166 "# sequence ID: consecutively increasing ID \n" +
00167 "uint32 seq\n" +
00168 "#Two-integer timestamp that is expressed as:\n" +
00169 "# * stamp.secs: seconds (stamp_secs) since epoch\n" +
00170 "# * stamp.nsecs: nanoseconds since stamp_secs\n" +
00171 "# time-handling sugar is provided by the client library\n" +
00172 "time stamp\n" +
00173 "#Frame this data is associated with\n" +
00174 "# 0: no frame\n" +
00175 "# 1: global frame\n" +
00176 "string frame_id\n" +
00177 "\n" +
00178 "================================================================================\n" +
00179 "MSG: sensor_msgs/RegionOfInterest\n" +
00180 "# This message is used to specify a region of interest within an image.\n" +
00181 "#\n" +
00182 "# When used to specify the ROI setting of the camera when the image was\n" +
00183 "# taken, the height and width fields should either match the height and\n" +
00184 "# width fields for the associated image; or height = width = 0\n" +
00185 "# indicates that the full resolution image was captured.\n" +
00186 "\n" +
00187 "uint32 x_offset # Leftmost pixel of the ROI\n" +
00188 " # (0 if the ROI includes the left edge of the image)\n" +
00189 "uint32 y_offset # Topmost pixel of the ROI\n" +
00190 " # (0 if the ROI includes the top edge of the image)\n" +
00191 "uint32 height # Height of ROI\n" +
00192 "uint32 width # Width of ROI\n" +
00193 "\n" +
00194 "# True if a distinct rectified ROI should be calculated from the \"raw\"\n" +
00195 "# ROI in this message. Typically this should be False if the full image\n" +
00196 "# is captured (ROI not used), and True if a subwindow is captured (ROI\n" +
00197 "# used).\n" +
00198 "bool do_rectify\n" +
00199 "\n" +
00200 ""; }
00201 public java.lang.String getMessageDefinition() { return __s_getMessageDefinition(); }
00202
00203 public CameraInfo clone() {
00204 CameraInfo c = new CameraInfo();
00205 c.deserialize(serialize(0));
00206 return c;
00207 }
00208
00209 public void setTo(ros.communication.Message m) {
00210 deserialize(m.serialize(0));
00211 }
00212
00213 public int serializationLength() {
00214 int __l = 0;
00215 __l += header.serializationLength();
00216 __l += 4;
00217 __l += 4;
00218 __l += 4 + distortion_model.length();
00219 __l += 4 + D.length * 8;
00220 __l += 72;
00221 __l += 72;
00222 __l += 96;
00223 __l += 4;
00224 __l += 4;
00225 __l += roi.serializationLength();
00226 return __l;
00227 }
00228
00229 public void serialize(ByteBuffer bb, int seq) {
00230 header.serialize(bb, seq);
00231 bb.putInt((int)height);
00232 bb.putInt((int)width);
00233 Serialization.writeString(bb, distortion_model);
00234 bb.putInt(D.length);
00235 for(double val : D) {
00236 bb.putDouble(val);
00237 }
00238
00239 for(double val : K) {
00240 bb.putDouble(val);
00241 }
00242
00243 for(double val : R) {
00244 bb.putDouble(val);
00245 }
00246
00247 for(double val : P) {
00248 bb.putDouble(val);
00249 }
00250 bb.putInt((int)binning_x);
00251 bb.putInt((int)binning_y);
00252 roi.serialize(bb, seq);
00253 }
00254
00255 public void deserialize(ByteBuffer bb) {
00256 header.deserialize(bb);
00257 height = (long)(bb.getInt() & 0xffffffff);
00258 width = (long)(bb.getInt() & 0xffffffff);
00259 distortion_model = Serialization.readString(bb);
00260
00261 int __D_len = bb.getInt();
00262 D = new double[__D_len];
00263 for(int __i=0; __i<__D_len; __i++) {
00264 D[__i] = bb.getDouble();
00265 }
00266
00267 int __K_len = K.length;;
00268 K = new double[__K_len];
00269 for(int __i=0; __i<__K_len; __i++) {
00270 K[__i] = bb.getDouble();
00271 }
00272
00273 int __R_len = R.length;;
00274 R = new double[__R_len];
00275 for(int __i=0; __i<__R_len; __i++) {
00276 R[__i] = bb.getDouble();
00277 }
00278
00279 int __P_len = P.length;;
00280 P = new double[__P_len];
00281 for(int __i=0; __i<__P_len; __i++) {
00282 P[__i] = bb.getDouble();
00283 }
00284 binning_x = (long)(bb.getInt() & 0xffffffff);
00285 binning_y = (long)(bb.getInt() & 0xffffffff);
00286 roi.deserialize(bb);
00287 }
00288
00289 @SuppressWarnings("all")
00290 public boolean equals(Object o) {
00291 if(!(o instanceof CameraInfo))
00292 return false;
00293 CameraInfo other = (CameraInfo) o;
00294 return
00295 header.equals(other.header) &&
00296 height == other.height &&
00297 width == other.width &&
00298 distortion_model.equals(other.distortion_model) &&
00299 java.util.Arrays.equals(D, other.D) &&
00300 java.util.Arrays.equals(K, other.K) &&
00301 java.util.Arrays.equals(R, other.R) &&
00302 java.util.Arrays.equals(P, other.P) &&
00303 binning_x == other.binning_x &&
00304 binning_y == other.binning_y &&
00305 roi.equals(other.roi) &&
00306 true;
00307 }
00308
00309 @SuppressWarnings("all")
00310 public int hashCode() {
00311 final int prime = 31;
00312 int result = 1;
00313 long tmp;
00314 result = prime * result + (this.header == null ? 0 : this.header.hashCode());
00315 result = prime * result + (int)(this.height ^ (this.height >>> 32));
00316 result = prime * result + (int)(this.width ^ (this.width >>> 32));
00317 result = prime * result + (this.distortion_model == null ? 0 : this.distortion_model.hashCode());
00318 result = prime * result + java.util.Arrays.hashCode(this.D);
00319 result = prime * result + java.util.Arrays.hashCode(this.K);
00320 result = prime * result + java.util.Arrays.hashCode(this.R);
00321 result = prime * result + java.util.Arrays.hashCode(this.P);
00322 result = prime * result + (int)(this.binning_x ^ (this.binning_x >>> 32));
00323 result = prime * result + (int)(this.binning_y ^ (this.binning_y >>> 32));
00324 result = prime * result + (this.roi == null ? 0 : this.roi.hashCode());
00325 return result;
00326 }
00327 }
00328