Class: Sensor_msgs::SetCameraInfoRequest

Inherits:
ROS::Message
  • Object
show all
Defined in:
lib/sensor_msgs/SetCameraInfo.rb

Constant Summary collapse

@@struct_L6C =
::ROS::Struct.new("L6C")
@@struct_L3 =
::ROS::Struct.new("L3")
@@struct_d12 =
::ROS::Struct.new("d12")
@@struct_L2 =
::ROS::Struct.new("L2")
@@struct_d9 =
::ROS::Struct.new("d9")
@@struct_L =
::ROS::Struct.new("L")
@@slot_types =
['sensor_msgs/CameraInfo']

Instance Attribute Summary collapse

Class Method Summary collapse

Instance Method Summary collapse

Constructor Details

#initialize(args = {}) ⇒ SetCameraInfoRequest

Constructor. You can set the default values using keyword operators.

Parameters:

  • args (Hash) (defaults to: {})

    keyword for initializing values

Options Hash (args):

  • :camera_info (sensor_msgs/CameraInfo)

    initialize value



225
226
227
228
229
230
231
232
# File 'lib/sensor_msgs/SetCameraInfo.rb', line 225

def initialize(args={})
  # message fields cannot be None, assign default values for those that are
  if args[:camera_info]
    @camera_info = args[:camera_info]
  else
    @camera_info = Sensor_msgs::CameraInfo.new
  end
end

Instance Attribute Details

#camera_infoObject

Returns the value of attribute camera_info.



210
211
212
# File 'lib/sensor_msgs/SetCameraInfo.rb', line 210

def camera_info
  @camera_info
end

Class Method Details

.md5sumObject



11
12
13
# File 'lib/sensor_msgs/SetCameraInfo.rb', line 11

def self.md5sum
  "ee34be01fdeee563d0d99cd594d5581d"
end

.typeObject



15
16
17
# File 'lib/sensor_msgs/SetCameraInfo.rb', line 15

def self.type
  "sensor_msgs/SetCameraInfoRequest"
end

Instance Method Details

#_get_typesString

internal API method

Returns:

  • (String)

    Message type string.



236
237
238
# File 'lib/sensor_msgs/SetCameraInfo.rb', line 236

def _get_types
  @slot_types
end

#deserialize(str) ⇒ Object

unpack serialized message in str into this message instance

@param [String] str: byte array of serialized message


268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
# File 'lib/sensor_msgs/SetCameraInfo.rb', line 268

def deserialize(str)

  begin
    if @camera_info == nil
      @camera_info = Sensor_msgs::CameraInfo.new
    end
    end_point = 0
    start = end_point
    end_point += ROS::Struct::calc_size('L3')
    (@camera_info.header.seq, @camera_info.header.stamp.secs, @camera_info.header.stamp.nsecs,) = @@struct_L3.unpack(str[start..(end_point-1)])
    start = end_point
    end_point += 4
    (length,) = @@struct_L.unpack(str[start..(end_point-1)])
    start = end_point
    end_point += length
    @camera_info.header.frame_id = str[start..(end_point-1)]
    start = end_point
    end_point += ROS::Struct::calc_size('L2')
    (@camera_info.height, @camera_info.width,) = @@struct_L2.unpack(str[start..(end_point-1)])
    start = end_point
    end_point += 4
    (length,) = @@struct_L.unpack(str[start..(end_point-1)])
    start = end_point
    end_point += length
    @camera_info.distortion_model = str[start..(end_point-1)]
    start = end_point
    end_point += 4
    (length,) = @@struct_L.unpack(str[start..(end_point-1)])
    pattern = "d#{length}"
    start = end_point
    end_point += ROS::Struct::calc_size("#{pattern}")
    @camera_info.D = str[start..(end_point-1)].unpack(pattern)
    start = end_point
    end_point += 8
    @camera_info.K = @@struct_d9.unpack(str[start..(end_point-1)])
    start = end_point
    end_point += 8
    @camera_info.R = @@struct_d9.unpack(str[start..(end_point-1)])
    start = end_point
    end_point += 8
    @camera_info.P = @@struct_d12.unpack(str[start..(end_point-1)])
    start = end_point
    end_point += ROS::Struct::calc_size('L6C')
    (@camera_info.binning_x, @camera_info.binning_y, @camera_info.roi.x_offset, @camera_info.roi.y_offset, @camera_info.roi.height, @camera_info.roi.width, @camera_info.roi.do_rectify,) = @@struct_L6C.unpack(str[start..(end_point-1)])
    @camera_info.roi.do_rectify = bool(@camera_info.roi.do_rectify)
    return self
  rescue => exception
    raise "message DeserializationError: #{exception}" #most likely buffer underfill
  end
end

#has_header?Boolean

Returns:

  • (Boolean)


19
20
21
# File 'lib/sensor_msgs/SetCameraInfo.rb', line 19

def has_header?
  false
end

#message_definitionObject



23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
# File 'lib/sensor_msgs/SetCameraInfo.rb', line 23

def message_definition
  "







sensor_msgs/CameraInfo camera_info

================================================================================
MSG: sensor_msgs/CameraInfo
# This message defines meta information for a camera. It should be in a
# camera namespace on topic \"camera_info\" and accompanied by up to five
# image topics named:
#
#   image_raw - raw data from the camera driver, possibly Bayer encoded
#   image            - monochrome, distorted
#   image_color      - color, distorted
#   image_rect       - monochrome, rectified
#   image_rect_color - color, rectified
#
# The image_pipeline contains packages (image_proc, stereo_image_proc)
# for producing the four processed image topics from image_raw and
# camera_info. The meaning of the camera parameters are described in
# detail at http://www.ros.org/wiki/image_pipeline/CameraInfo.
#
# The image_geometry package provides a user-friendly interface to
# common operations using this meta information. If you want to, e.g.,
# project a 3d point into image coordinates, we strongly recommend
# using image_geometry.
#
# If the camera is uncalibrated, the matrices D, K, R, P should be left
# zeroed out. In particular, clients may assume that K[0] == 0.0
# indicates an uncalibrated camera.

#######################################################################
#                     Image acquisition info                          #
#######################################################################

# Time of image acquisition, camera coordinate frame ID
Header header    # Header timestamp should be acquisition time of image
               # Header frame_id should be optical frame of camera
               # origin of frame should be optical center of camera
               # +x should point to the right in the image
               # +y should point down in the image
               # +z should point into the plane of the image


#######################################################################
#                      Calibration Parameters                         #
#######################################################################
# These are fixed during camera calibration. Their values will be the #
# same in all messages until the camera is recalibrated. Note that    #
# self-calibrating systems may \"recalibrate\" frequently.              #
#                                                                     #
# The internal parameters can be used to warp a raw (distorted) image #
# to:                                                                 #
#   1. An undistorted image (requires D and K)                        #
#   2. A rectified image (requires D, K, R)                           #
# The projection matrix P projects 3D points into the rectified image.#
#######################################################################

# The image dimensions with which the camera was calibrated. Normally
# this will be the full camera resolution in pixels.
uint32 height
uint32 width

# The distortion model used. Supported models are listed in
# sensor_msgs/distortion_models.h. For most cameras, \"plumb_bob\" - a
# simple model of radial and tangential distortion - is sufficent.
string distortion_model

# The distortion parameters, size depending on the distortion model.
# For \"plumb_bob\", the 5 parameters are: (k1, k2, t1, t2, k3).
float64[] D

# Intrinsic camera matrix for the raw (distorted) images.
#     [fx  0 cx]
# K = [ 0 fy cy]
#     [ 0  0  1]
# Projects 3D points in the camera coordinate frame to 2D pixel
# coordinates using the focal lengths (fx, fy) and principal point
# (cx, cy).
float64[9]  K # 3x3 row-major matrix

# Rectification matrix (stereo cameras only)
# A rotation matrix aligning the camera coordinate system to the ideal
# stereo image plane so that epipolar lines in both stereo images are
# parallel.
float64[9]  R # 3x3 row-major matrix

# Projection/camera matrix
#     [fx'  0  cx' Tx]
# P = [ 0  fy' cy' Ty]
#     [ 0   0   1   0]
# By convention, this matrix specifies the intrinsic (camera) matrix
#  of the processed (rectified) image. That is, the left 3x3 portion
#  is the normal camera intrinsic matrix for the rectified image.
# It projects 3D points in the camera coordinate frame to 2D pixel
#  coordinates using the focal lengths (fx', fy') and principal point
#  (cx', cy') - these may differ from the values in K.
# For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will
#  also have R = the identity and P[1:3,1:3] = K.
# For a stereo pair, the fourth column [Tx Ty 0]' is related to the
#  position of the optical center of the second camera in the first
#  camera's frame. We assume Tz = 0 so both cameras are in the same
#  stereo image plane. The first camera always has Tx = Ty = 0. For
#  the right (second) camera of a horizontal stereo pair, Ty = 0 and
#  Tx = -fx' * B, where B is the baseline between the cameras.
# Given a 3D point [X Y Z]', the projection (x, y) of the point onto
#  the rectified image is given by:
#  [u v w]' = P * [X Y Z 1]'
#         x = u / w
#         y = v / w
#  This holds for both images of a stereo pair.
float64[12] P # 3x4 row-major matrix


#######################################################################
#                      Operational Parameters                         #
#######################################################################
# These define the image region actually captured by the camera       #
# driver. Although they affect the geometry of the output image, they #
# may be changed freely without recalibrating the camera.             #
#######################################################################

# Binning refers here to any camera setting which combines rectangular
#  neighborhoods of pixels into larger \"super-pixels.\" It reduces the
#  resolution of the output image to
#  (width / binning_x) x (height / binning_y).
# The default values binning_x = binning_y = 0 is considered the same
#  as binning_x = binning_y = 1 (no subsampling).
uint32 binning_x
uint32 binning_y

# Region of interest (subwindow of full camera resolution), given in
#  full resolution (unbinned) image coordinates. A particular ROI
#  always denotes the same window of pixels on the camera sensor,
#  regardless of binning settings.
# The default setting of roi (all values 0) is considered the same as
#  full resolution (roi.width = width, roi.height = height).
RegionOfInterest roi

================================================================================
MSG: std_msgs/Header
# Standard metadata for higher-level stamped data types.
# This is generally used to communicate timestamped data 
# in a particular coordinate frame.
# 
# sequence ID: consecutively increasing ID 
uint32 seq
#Two-integer timestamp that is expressed as:
# * stamp.secs: seconds (stamp_secs) since epoch
# * stamp.nsecs: nanoseconds since stamp_secs
# time-handling sugar is provided by the client library
time stamp
#Frame this data is associated with
# 0: no frame
# 1: global frame
string frame_id

================================================================================
MSG: sensor_msgs/RegionOfInterest
# This message is used to specify a region of interest within an image.
#
# When used to specify the ROI setting of the camera when the image was
# taken, the height and width fields should either match the height and
# width fields for the associated image; or height = width = 0
# indicates that the full resolution image was captured.

uint32 x_offset  # Leftmost pixel of the ROI
               # (0 if the ROI includes the left edge of the image)
uint32 y_offset  # Topmost pixel of the ROI
               # (0 if the ROI includes the top edge of the image)
uint32 height    # Height of ROI
uint32 width     # Width of ROI

# True if a distinct rectified ROI should be calculated from the \"raw\"
# ROI in this message. Typically this should be False if the full image
# is captured (ROI not used), and True if a subwindow is captured (ROI
# used).
bool do_rectify

"
end

#serialize(buff) ⇒ Object

serialize message into buffer

Parameters:

  • buff (IO)

    buffer



242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
# File 'lib/sensor_msgs/SetCameraInfo.rb', line 242

def serialize(buff)
  begin
    buff.write(@@struct_L3.pack(@camera_info.header.seq, @camera_info.header.stamp.secs, @camera_info.header.stamp.nsecs))
    _x = @camera_info.header.frame_id
    length = _x.length
    buff.write([length, _x].pack("La#{length}"))
    buff.write(@@struct_L2.pack(@camera_info.height, @camera_info.width))
    _x = @camera_info.distortion_model
    length = _x.length
    buff.write([length, _x].pack("La#{length}"))
    length = @camera_info.D.length
    buff.write(@@struct_L.pack(length))
    pattern = "d#{length}"
    buff.write(*@camera_info.D.pack(pattern))
    buff.write(@@struct_d9.pack(*@camera_info.K))
    buff.write(@@struct_d9.pack(*@camera_info.R))
    buff.write(@@struct_d12.pack(*@camera_info.P))
    buff.write(@@struct_L6C.pack(@camera_info.binning_x, @camera_info.binning_y, @camera_info.roi.x_offset, @camera_info.roi.y_offset, @camera_info.roi.height, @camera_info.roi.width, @camera_info.roi.do_rectify))
  rescue => exception
    raise "some erro in serialize: #{exception}"

  end
end