Cameras¶
Abstract interface¶
Abstract camera interface for recording and conversion
Camera
¶
Bases: ABC
Abstract base class for cameras.
Supports two usage modes: - Live recording: open() → start_recording(path) → grab() loop → stop_recording() → close() - File playback: open_file(path) → grab() loop → get_frame() → close()
Source code in raiden/cameras/base.py
name
abstractmethod
property
¶
Semantic name assigned to this camera (e.g. 'scene_camera')
recording_extension
abstractmethod
property
¶
File extension used for native recording (e.g. 'svo2', 'bag')
serial_number
abstractmethod
property
¶
Camera hardware serial number as string
close()
abstractmethod
¶
get_current_timestamp_ns()
¶
Current host time in nanoseconds.
The default implementation uses time.time_ns(). Camera subclasses
that have their own hardware clock (e.g. ZED) should override this so
that the returned value is on the same clock as CameraFrame.timestamp_ns,
enabling direct interpolation between robot data and camera frames.
Source code in raiden/cameras/base.py
get_frame()
abstractmethod
¶
Retrieve color and depth from the most recently grabbed frame.
Only valid to call after a successful grab().
get_intrinsics()
abstractmethod
¶
Return factory-calibrated camera intrinsics.
These come directly from the camera SDK (ZED factory calibration, RealSense on-device calibration) rather than being computed from images.
Returns:
| Name | Type | Description |
|---|---|---|
camera_matrix |
ndarray
|
3x3 float64 array |
dist_coeffs |
ndarray
|
1-D float64 array |
image_size |
Tuple[int, int]
|
|
Source code in raiden/cameras/base.py
grab()
abstractmethod
¶
Grab the next available frame.
Blocks until a frame is ready (rate-limited to camera FPS). While recording is active, the frame is also written to the output file.
Returns:
| Type | Description |
|---|---|
bool
|
True on success, False on error or end-of-file |
Source code in raiden/cameras/base.py
open()
abstractmethod
¶
start_recording(path)
abstractmethod
¶
Begin recording to file.
For ZED this enables SVO2 recording; every subsequent grab() is stored. For RealSense this starts a .bag recorder.
CameraFrame
dataclass
¶
ZED camera¶
ZED stereo camera implementation using the pyzed SDK.
opens by serial number, records to SVO2 (H264).
Depth is NOT computed during recording (depth_mode=NONE) for lower CPU usage; the raw stereo pair is stored instead.
Playback mode : opens an SVO2 file, computes depth (NEURAL) for each frame. Use ZedCamera.from_svo() to create a playback instance.
ZedCamera
¶
Bases: Camera
ZED camera – records to .svo2
Source code in raiden/cameras/zed.py
19 20 21 22 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 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 | |
from_svo(camera_name, svo_path, compute_sdk_depth=True)
classmethod
¶
Open an SVO2 file for frame-by-frame extraction.
Parameters¶
compute_sdk_depth : bool If True (default) depth is computed by the ZED SDK (NEURAL_LIGHT). Set to False when you will compute depth externally (e.g. with FFS); this skips the SDK depth pass for lower CPU/GPU load.
Source code in raiden/cameras/zed.py
get_camera_info()
¶
Return camera intrinsics and metadata as a plain dict.
Source code in raiden/cameras/zed.py
get_current_timestamp_ns()
¶
Current host time in nanoseconds via the ZED SDK.
On the same clock as get_frame_timestamp_ns(), so robot observations
recorded with this value can be directly interpolated against camera
frame timestamps.
Source code in raiden/cameras/zed.py
get_frame()
¶
Retrieve color (and depth if in playback mode) from last grab.
Source code in raiden/cameras/zed.py
get_frame_timestamp_ns()
¶
Timestamp of the most recently grabbed frame in nanoseconds (ZED hardware clock).
get_intrinsics()
¶
Return ZED SDK factory-calibrated intrinsics for the left lens.
Source code in raiden/cameras/zed.py
get_right_color()
¶
Return the right-camera BGR image for the most recently grabbed frame.
Only valid after a successful grab(). Used by external stereo depth predictors (e.g. Fast Foundation Stereo) that need both views.
Source code in raiden/cameras/zed.py
get_stereo_calib()
¶
Return (fx, baseline_m) for the left camera at the current resolution.
fx is the left-camera focal length in pixels and baseline_m is
the stereo baseline in metres. Used to convert FFS disparity to depth.
Source code in raiden/cameras/zed.py
get_total_frames()
¶
grab()
¶
Grab next frame (blocks until ready at camera FPS).
open()
¶
Open live camera. Depth is disabled to reduce recording overhead.
Source code in raiden/cameras/zed.py
start_recording(path)
¶
Enable SVO2 recording. Every subsequent grab() writes a frame.
Source code in raiden/cameras/zed.py
RealSense camera¶
Intel RealSense camera implementation (e.g. D405).
Recording mode opens by serial number and records to .bag via the SDK recorder.
Playback mode opens a .bag file and reads color + depth frames;
use RealSenseCamera.from_bag() to create a playback instance.
.. warning:: For dynamic tasks, prefer ZED cameras over RealSense. RealSense cameras have known synchronization limitations that make them less suitable for capturing fast robot motion. See Synchronization issues below for details.
Intrinsics note¶
RealSense cameras store per-device calibration on-board. get_intrinsics() reads the color stream's Brown-Conrady coefficients directly from the SDK, which is the same model OpenCV uses, so the values can be passed straight to cv2 functions without any conversion.
Synchronization issues¶
RealSense cameras (especially the D405) have several properties that make multi-camera synchronization harder than with ZED cameras:
Timestamp reliability
The global_time_enabled option is supposed to stamp frames with the
host wall-clock time, but support is inconsistent across D4xx firmware
versions. When it is not supported, the SDK reports hardware-relative
timestamps (milliseconds since device boot) that must be converted to
wall-clock time. _measure_clock_offset() compensates for this by
measuring the offset between the first frame timestamp and
time.time_ns() at recording start, but this is only an approximation.
Frame extraction drain-loop bug
The RealSense SDK pre-buffers frames during bag playback when
set_real_time(False) is set. A naive "drain the queue to get the
latest frame" loop (appropriate for live preview) will consume every
other buffered frame, halving the apparent FPS to ~15 fps even when the
bag was recorded at 30 fps. grab() therefore skips the drain loop
in playback mode (_is_playback = True).
Recommendation
Use ZED cameras for scene and wrist cameras in dynamic manipulation
tasks. ZED timestamps (sl.TIME_REFERENCE.IMAGE) are wall-clock
Unix nanoseconds, consistent across cameras and with the robot
controller clock, making multi-camera alignment straightforward.
RealSense cameras are best suited for static or slow-motion scenes
where their close-range depth quality is the primary requirement.
RealSenseCamera
¶
Bases: Camera
Intel RealSense D4xx camera – records to .bag
Source code in raiden/cameras/realsense.py
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 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 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 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 | |
from_bag(camera_name, bag_path)
classmethod
¶
Open a .bag file for frame-by-frame extraction.
Source code in raiden/cameras/realsense.py
get_camera_info()
¶
Return camera intrinsics and metadata as a plain dict.
Source code in raiden/cameras/realsense.py
get_current_timestamp_ns()
¶
Return the capture timestamp of the most recently grabbed frame.
With global_time_enabled the RealSense SDK stamps frames with system wall-clock time, so this is on the same clock as time.time_ns() and can be used directly to align robot data with camera frames.
Source code in raiden/cameras/realsense.py
get_intrinsics()
¶
Return on-device calibrated intrinsics for the color stream.
RealSense stores per-unit calibration on-board. The distortion model is Brown-Conrady (identical to OpenCV's), so coefficients are directly usable with cv2 functions.
Source code in raiden/cameras/realsense.py
start_recording(path)
¶
Restart pipeline with bag recorder attached.
Source code in raiden/cameras/realsense.py
stop_recording()
¶
Restart pipeline without recorder to finalize the bag file.