|
YARP
Yet Another Robot Platform
|
|
Go to the documentation of this file.
27 #ifndef YARP_ROSMSG_sensor_msgs_SetCameraInfo_h
28 #define YARP_ROSMSG_sensor_msgs_SetCameraInfo_h
127 static constexpr
const char*
typeName =
"sensor_msgs/SetCameraInfo";
130 static constexpr
const char*
typeChecksum =
"ee34be01fdeee563d0d99cd594d5581d";
134 # This service requests that a camera stores the given CameraInfo \n\
135 # as that camera's calibration information.\n\
137 # The width and height in the camera_info field should match what the\n\
138 # camera is currently outputting on its camera_info topic, and the camera\n\
139 # will assume that the region of the imager that is being referred to is\n\
140 # the region that the camera is currently capturing.\n\
142 sensor_msgs/CameraInfo camera_info # The camera_info to store\n\
144 bool success # True if the call succeeded\n\
145 string status_message # Used to give details about success\n\
147 ================================================================================\n\
148 MSG: sensor_msgs/CameraInfo\n\
149 # This message defines meta information for a camera. It should be in a\n\
150 # camera namespace on topic \"camera_info\" and accompanied by up to five\n\
151 # image topics named:\n\
153 # image_raw - raw data from the camera driver, possibly Bayer encoded\n\
154 # image - monochrome, distorted\n\
155 # image_color - color, distorted\n\
156 # image_rect - monochrome, rectified\n\
157 # image_rect_color - color, rectified\n\
159 # The image_pipeline contains packages (image_proc, stereo_image_proc)\n\
160 # for producing the four processed image topics from image_raw and\n\
161 # camera_info. The meaning of the camera parameters are described in\n\
162 # detail at http://www.ros.org/wiki/image_pipeline/CameraInfo.\n\
164 # The image_geometry package provides a user-friendly interface to\n\
165 # common operations using this meta information. If you want to, e.g.,\n\
166 # project a 3d point into image coordinates, we strongly recommend\n\
167 # using image_geometry.\n\
169 # If the camera is uncalibrated, the matrices D, K, R, P should be left\n\
170 # zeroed out. In particular, clients may assume that K[0] == 0.0\n\
171 # indicates an uncalibrated camera.\n\
173 #######################################################################\n\
174 # Image acquisition info #\n\
175 #######################################################################\n\
177 # Time of image acquisition, camera coordinate frame ID\n\
178 Header header # Header timestamp should be acquisition time of image\n\
179 # Header frame_id should be optical frame of camera\n\
180 # origin of frame should be optical center of camera\n\
181 # +x should point to the right in the image\n\
182 # +y should point down in the image\n\
183 # +z should point into the plane of the image\n\
186 #######################################################################\n\
187 # Calibration Parameters #\n\
188 #######################################################################\n\
189 # These are fixed during camera calibration. Their values will be the #\n\
190 # same in all messages until the camera is recalibrated. Note that #\n\
191 # self-calibrating systems may \"recalibrate\" frequently. #\n\
193 # The internal parameters can be used to warp a raw (distorted) image #\n\
195 # 1. An undistorted image (requires D and K) #\n\
196 # 2. A rectified image (requires D, K, R) #\n\
197 # The projection matrix P projects 3D points into the rectified image.#\n\
198 #######################################################################\n\
200 # The image dimensions with which the camera was calibrated. Normally\n\
201 # this will be the full camera resolution in pixels.\n\
205 # The distortion model used. Supported models are listed in\n\
206 # sensor_msgs/distortion_models.h. For most cameras, \"plumb_bob\" - a\n\
207 # simple model of radial and tangential distortion - is sufficient.\n\
208 string distortion_model\n\
210 # The distortion parameters, size depending on the distortion model.\n\
211 # For \"plumb_bob\", the 5 parameters are: (k1, k2, t1, t2, k3).\n\
214 # Intrinsic camera matrix for the raw (distorted) images.\n\
218 # Projects 3D points in the camera coordinate frame to 2D pixel\n\
219 # coordinates using the focal lengths (fx, fy) and principal point\n\
221 float64[9] K # 3x3 row-major matrix\n\
223 # Rectification matrix (stereo cameras only)\n\
224 # A rotation matrix aligning the camera coordinate system to the ideal\n\
225 # stereo image plane so that epipolar lines in both stereo images are\n\
227 float64[9] R # 3x3 row-major matrix\n\
229 # Projection/camera matrix\n\
231 # P = [ 0 fy' cy' Ty]\n\
233 # By convention, this matrix specifies the intrinsic (camera) matrix\n\
234 # of the processed (rectified) image. That is, the left 3x3 portion\n\
235 # is the normal camera intrinsic matrix for the rectified image.\n\
236 # It projects 3D points in the camera coordinate frame to 2D pixel\n\
237 # coordinates using the focal lengths (fx', fy') and principal point\n\
238 # (cx', cy') - these may differ from the values in K.\n\
239 # For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will\n\
240 # also have R = the identity and P[1:3,1:3] = K.\n\
241 # For a stereo pair, the fourth column [Tx Ty 0]' is related to the\n\
242 # position of the optical center of the second camera in the first\n\
243 # camera's frame. We assume Tz = 0 so both cameras are in the same\n\
244 # stereo image plane. The first camera always has Tx = Ty = 0. For\n\
245 # the right (second) camera of a horizontal stereo pair, Ty = 0 and\n\
246 # Tx = -fx' * B, where B is the baseline between the cameras.\n\
247 # Given a 3D point [X Y Z]', the projection (x, y) of the point onto\n\
248 # the rectified image is given by:\n\
249 # [u v w]' = P * [X Y Z 1]'\n\
252 # This holds for both images of a stereo pair.\n\
253 float64[12] P # 3x4 row-major matrix\n\
256 #######################################################################\n\
257 # Operational Parameters #\n\
258 #######################################################################\n\
259 # These define the image region actually captured by the camera #\n\
260 # driver. Although they affect the geometry of the output image, they #\n\
261 # may be changed freely without recalibrating the camera. #\n\
262 #######################################################################\n\
264 # Binning refers here to any camera setting which combines rectangular\n\
265 # neighborhoods of pixels into larger \"super-pixels.\" It reduces the\n\
266 # resolution of the output image to\n\
267 # (width / binning_x) x (height / binning_y).\n\
268 # The default values binning_x = binning_y = 0 is considered the same\n\
269 # as binning_x = binning_y = 1 (no subsampling).\n\
273 # Region of interest (subwindow of full camera resolution), given in\n\
274 # full resolution (unbinned) image coordinates. A particular ROI\n\
275 # always denotes the same window of pixels on the camera sensor,\n\
276 # regardless of binning settings.\n\
277 # The default setting of roi (all values 0) is considered the same as\n\
278 # full resolution (roi.width = width, roi.height = height).\n\
279 RegionOfInterest roi\n\
281 ================================================================================\n\
282 MSG: std_msgs/Header\n\
283 # Standard metadata for higher-level stamped data types.\n\
284 # This is generally used to communicate timestamped data \n\
285 # in a particular coordinate frame.\n\
287 # sequence ID: consecutively increasing ID \n\
289 #Two-integer timestamp that is expressed as:\n\
290 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
291 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
292 # time-handling sugar is provided by the client library\n\
294 #Frame this data is associated with\n\
299 ================================================================================\n\
300 MSG: sensor_msgs/RegionOfInterest\n\
301 # This message is used to specify a region of interest within an image.\n\
303 # When used to specify the ROI setting of the camera when the image was\n\
304 # taken, the height and width fields should either match the height and\n\
305 # width fields for the associated image; or height = width = 0\n\
306 # indicates that the full resolution image was captured.\n\
308 uint32 x_offset # Leftmost pixel of the ROI\n\
309 # (0 if the ROI includes the left edge of the image)\n\
310 uint32 y_offset # Topmost pixel of the ROI\n\
311 # (0 if the ROI includes the top edge of the image)\n\
312 uint32 height # Height of ROI\n\
313 uint32 width # Width of ROI\n\
315 # True if a distinct rectified ROI should be calculated from the \"raw\"\n\
316 # ROI in this message. Typically this should be False if the full image\n\
317 # is captured (ROI not used), and True if a subwindow is captured (ROI\n\
335 #endif // YARP_ROSMSG_sensor_msgs_SetCameraInfo_h
bool readBottle(yarp::os::ConnectionReader &connection) override
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
virtual bool read(yarp::os::idl::WireReader &reader)
yarp::rosmsg::sensor_msgs::CameraInfo camera_info
virtual bool isBareMode() const =0
Check if the connection is bare mode.
yarp::os::idl::BottleStyle< yarp::rosmsg::sensor_msgs::SetCameraInfo > bottleStyle
bool writeBare(yarp::os::ConnectionWriter &connection) const override
static constexpr const char * typeName
bool readBare(yarp::os::ConnectionReader &connection) override
virtual bool isError() const =0
static Type byName(const char *name)
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
Type & addProperty(const char *key, const Value &val)
An interface for writing to a network connection.
virtual bool isError() const =0
yarp::os::Type getType() const override
virtual bool convertTextMode()=0
Reads in a standard description in text mode, and converts it to a standard description in binary.
A "tamed" Portable, that promises to serialize itself in an IDL-friendly way.
virtual bool isBareMode() const =0
Check if the connection is bare mode.
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.
IDL-friendly connection reader.
An interface for reading from a network connection.
The main, catch-all namespace for YARP.
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
static constexpr const char * typeChecksum
A single value (typically within a Bottle).
yarp::os::idl::BareStyle< yarp::rosmsg::sensor_msgs::SetCameraInfo > rosStyle
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
virtual bool write(const yarp::os::idl::WireWriter &writer) const
static constexpr const char * typeText