align.cpp
Go to the documentation of this file.
1 // License: Apache 2.0. See LICENSE file in root directory.
2 // Copyright(c) 2017 Intel Corporation. All Rights Reserved.
3 
4 #include "../include/librealsense2/hpp/rs_sensor.hpp"
5 #include "../include/librealsense2/hpp/rs_processing.hpp"
6 
7 #include "core/video.h"
9 #include "environment.h"
10 #include "align.h"
11 #include "stream.h"
12 
13 namespace librealsense
14 {
15  template<int N> struct bytes { byte b[N]; };
16 
17  template<class GET_DEPTH, class TRANSFER_PIXEL>
18  void align_images(const rs2_intrinsics& depth_intrin, const rs2_extrinsics& depth_to_other,
19  const rs2_intrinsics& other_intrin, GET_DEPTH get_depth, TRANSFER_PIXEL transfer_pixel)
20  {
21  // Iterate over the pixels of the depth image
22 #pragma omp parallel for schedule(dynamic)
23  for (int depth_y = 0; depth_y < depth_intrin.height; ++depth_y)
24  {
25  int depth_pixel_index = depth_y * depth_intrin.width;
26  for (int depth_x = 0; depth_x < depth_intrin.width; ++depth_x, ++depth_pixel_index)
27  {
28  // Skip over depth pixels with the value of zero, we have no depth data so we will not write anything into our aligned images
29  if (float depth = get_depth(depth_pixel_index))
30  {
31  // Map the top-left corner of the depth pixel onto the other image
32  float depth_pixel[2] = { depth_x - 0.5f, depth_y - 0.5f }, depth_point[3], other_point[3], other_pixel[2];
33  rs2_deproject_pixel_to_point(depth_point, &depth_intrin, depth_pixel, depth);
34  rs2_transform_point_to_point(other_point, &depth_to_other, depth_point);
35  rs2_project_point_to_pixel(other_pixel, &other_intrin, other_point);
36  const int other_x0 = static_cast<int>(other_pixel[0] + 0.5f);
37  const int other_y0 = static_cast<int>(other_pixel[1] + 0.5f);
38 
39  // Map the bottom-right corner of the depth pixel onto the other image
40  depth_pixel[0] = depth_x + 0.5f; depth_pixel[1] = depth_y + 0.5f;
41  rs2_deproject_pixel_to_point(depth_point, &depth_intrin, depth_pixel, depth);
42  rs2_transform_point_to_point(other_point, &depth_to_other, depth_point);
43  rs2_project_point_to_pixel(other_pixel, &other_intrin, other_point);
44  const int other_x1 = static_cast<int>(other_pixel[0] + 0.5f);
45  const int other_y1 = static_cast<int>(other_pixel[1] + 0.5f);
46 
47  if (other_x0 < 0 || other_y0 < 0 || other_x1 >= other_intrin.width || other_y1 >= other_intrin.height)
48  continue;
49 
50  // Transfer between the depth pixels and the pixels inside the rectangle on the other image
51  for (int y = other_y0; y <= other_y1; ++y)
52  {
53  for (int x = other_x0; x <= other_x1; ++x)
54  {
55  transfer_pixel(depth_pixel_index, y * other_intrin.width + x);
56  }
57  }
58  }
59  }
60  }
61  }
62 
63  align::align(rs2_stream to_stream) : align(to_stream, "Align")
64  {}
65 
67  const rs2::video_frame& depth, const rs2::video_stream_profile& other_profile, float z_scale)
68  {
69  byte* aligned_data = reinterpret_cast<byte*>(const_cast<void*>(aligned.get_data()));
70  auto aligned_profile = aligned.get_profile().as<rs2::video_stream_profile>();
71  memset(aligned_data, 0, aligned_profile.height() * aligned_profile.width() * aligned.get_bytes_per_pixel());
72 
73  auto depth_profile = depth.get_profile().as<rs2::video_stream_profile>();
74 
75  auto z_intrin = depth_profile.get_intrinsics();
76  auto other_intrin = other_profile.get_intrinsics();
77  auto z_to_other = depth_profile.get_extrinsics_to(other_profile);
78 
79  auto z_pixels = reinterpret_cast<const uint16_t*>(depth.get_data());
80  auto out_z = (uint16_t *)(aligned_data);
81 
82  align_images(z_intrin, z_to_other, other_intrin,
83  [z_pixels, z_scale](int z_pixel_index) { return z_scale * z_pixels[z_pixel_index]; },
84  [out_z, z_pixels](int z_pixel_index, int other_pixel_index)
85  {
86  out_z[other_pixel_index] = out_z[other_pixel_index] ?
87  std::min((int)out_z[other_pixel_index], (int)z_pixels[z_pixel_index]) :
88  z_pixels[z_pixel_index];
89  });
90  }
91 
92  template<int N, class GET_DEPTH>
93  void align_other_to_depth_bytes(byte* other_aligned_to_depth, GET_DEPTH get_depth, const rs2_intrinsics& depth_intrin, const rs2_extrinsics& depth_to_other, const rs2_intrinsics& other_intrin, const byte* other_pixels)
94  {
95  auto in_other = (const bytes<N> *)(other_pixels);
96  auto out_other = (bytes<N> *)(other_aligned_to_depth);
97  align_images(depth_intrin, depth_to_other, other_intrin, get_depth,
98  [out_other, in_other](int depth_pixel_index, int other_pixel_index) { out_other[depth_pixel_index] = in_other[other_pixel_index]; });
99  }
100 
101  template<class GET_DEPTH>
102  void align_other_to_depth(byte* other_aligned_to_depth, GET_DEPTH get_depth, const rs2_intrinsics& depth_intrin, const rs2_extrinsics & depth_to_other, const rs2_intrinsics& other_intrin, const byte* other_pixels, rs2_format other_format)
103  {
104  switch (other_format)
105  {
106  case RS2_FORMAT_Y8:
107  align_other_to_depth_bytes<1>(other_aligned_to_depth, get_depth, depth_intrin, depth_to_other, other_intrin, other_pixels);
108  break;
109  case RS2_FORMAT_Y16:
110  case RS2_FORMAT_Z16:
111  align_other_to_depth_bytes<2>(other_aligned_to_depth, get_depth, depth_intrin, depth_to_other, other_intrin, other_pixels);
112  break;
113  case RS2_FORMAT_RGB8:
114  case RS2_FORMAT_BGR8:
115  align_other_to_depth_bytes<3>(other_aligned_to_depth, get_depth, depth_intrin, depth_to_other, other_intrin, other_pixels);
116  break;
117  case RS2_FORMAT_RGBA8:
118  case RS2_FORMAT_BGRA8:
119  align_other_to_depth_bytes<4>(other_aligned_to_depth, get_depth, depth_intrin, depth_to_other, other_intrin, other_pixels);
120  break;
121  default:
122  assert(false); // NOTE: rs2_align_other_to_depth_bytes<2>(...) is not appropriate for RS2_FORMAT_YUYV/RS2_FORMAT_RAW10 images, no logic prevents U/V channels from being written to one another
123  }
124  }
125 
126  void align::align_other_to_z(rs2::video_frame& aligned, const rs2::video_frame& depth, const rs2::video_frame& other, float z_scale)
127  {
128  byte* aligned_data = reinterpret_cast<byte*>(const_cast<void*>(aligned.get_data()));
129  auto aligned_profile = aligned.get_profile().as<rs2::video_stream_profile>();
130  memset(aligned_data, 0, aligned_profile.height() * aligned_profile.width() * aligned.get_bytes_per_pixel());
131 
132  auto depth_profile = depth.get_profile().as<rs2::video_stream_profile>();
134 
135  auto z_intrin = depth_profile.get_intrinsics();
136  auto other_intrin = other_profile.get_intrinsics();
137  auto z_to_other = depth_profile.get_extrinsics_to(other_profile);
138 
139  auto z_pixels = reinterpret_cast<const uint16_t*>(depth.get_data());
140  auto other_pixels = reinterpret_cast<const byte*>(other.get_data());
141 
142  align_other_to_depth(aligned_data, [z_pixels, z_scale](int z_pixel_index) { return z_scale * z_pixels[z_pixel_index]; },
143  z_intrin, z_to_other, other_intrin, other_pixels, other_profile.format());
144  }
145 
146  std::shared_ptr<rs2::video_stream_profile> align::create_aligned_profile(
147  rs2::video_stream_profile& original_profile,
149  {
150  auto from_to = std::make_pair(original_profile.get()->profile, to_profile.get()->profile);
151  auto it = _align_stream_unique_ids.find(from_to);
152  if (it != _align_stream_unique_ids.end())
153  {
154  return it->second;
155  }
156  auto aligned_profile = std::make_shared<rs2::video_stream_profile>(original_profile.clone(original_profile.stream_type(), original_profile.stream_index(), original_profile.format()));
157  aligned_profile->get()->profile->set_framerate(original_profile.fps());
158  if (auto original_video_profile = As<video_stream_profile_interface>(original_profile.get()->profile))
159  {
160  if (auto to_video_profile = As<video_stream_profile_interface>(to_profile.get()->profile))
161  {
162  if (auto aligned_video_profile = As<video_stream_profile_interface>(aligned_profile->get()->profile))
163  {
164  aligned_video_profile->set_dims(to_video_profile->get_width(), to_video_profile->get_height());
165  auto aligned_intrinsics = to_video_profile->get_intrinsics();
166  aligned_intrinsics.width = to_video_profile->get_width();
167  aligned_intrinsics.height = to_video_profile->get_height();
168  aligned_video_profile->set_intrinsics([aligned_intrinsics]() { return aligned_intrinsics; });
169  aligned_profile->register_extrinsics_to(to_profile, { { 1,0,0,0,1,0,0,0,1 },{ 0,0,0 } });
170  }
171  }
172  }
173  _align_stream_unique_ids[from_to] = aligned_profile;
174  reset_cache(original_profile.stream_type(), to_profile.stream_type());
175  return aligned_profile;
176  }
177 
179  {
180  if (!frame)
181  return false;
182 
183  auto set = frame.as<rs2::frameset>();
184  if (!set)
185  return false;
186 
187  auto profile = frame.get_profile();
188  rs2_stream stream = profile.stream_type();
190  int index = profile.stream_index();
191 
192  //process composite frame only if it contains both a depth frame and the requested texture frame
193  bool has_tex = false, has_depth = false;
194  set.foreach_rs([this, &has_tex](const rs2::frame& frame) { if (frame.get_profile().stream_type() == _to_stream_type) has_tex = true; });
195  set.foreach_rs([&has_depth](const rs2::frame& frame)
196  { if (frame.get_profile().stream_type() == RS2_STREAM_DEPTH && frame.get_profile().format() == RS2_FORMAT_Z16) has_depth = true; });
197  if (!has_tex || !has_depth)
198  return false;
199 
200  return true;
201  }
202 
204  {
206  return ext;
207  }
208 
210  {
211  rs2::frame rv;
212  auto from_bytes_per_pixel = from.get_bytes_per_pixel();
213 
214  auto from_profile = from.get_profile().as<rs2::video_stream_profile>();
216 
217  auto aligned_profile = create_aligned_profile(from_profile, to_profile);
218 
219  auto ext = select_extension(from);
220 
221  rv = source.allocate_video_frame(
222  *aligned_profile,
223  from,
224  from_bytes_per_pixel,
225  to.get_width(),
226  to.get_height(),
227  to.get_width() * from_bytes_per_pixel,
228  ext);
229  return rv;
230  }
231 
233  {
234  auto from_profile = from.get_profile().as<rs2::video_stream_profile>();
236 
237  auto aligned_profile = aligned.get_profile().as<rs2::video_stream_profile>();
238 
239  if (to_profile.stream_type() == RS2_STREAM_DEPTH)
240  {
241  align_other_to_z(aligned, to, from, _depth_scale);
242  }
243  else
244  {
245  align_z_to_other(aligned, from, to_profile, _depth_scale);
246  }
247  }
248 
250  {
251  rs2::frame rv;
252  std::vector<rs2::frame> output_frames;
253  std::vector<rs2::frame> other_frames;
254 
255  auto frames = f.as<rs2::frameset>();
256  auto depth = frames.first_or_default(RS2_STREAM_DEPTH, RS2_FORMAT_Z16).as<rs2::depth_frame>();
257 
258  _depth_scale = ((librealsense::depth_frame*)depth.get())->get_units();
259 
261  frames.foreach_rs([&other_frames](const rs2::frame& f) {if ((f.get_profile().stream_type() != RS2_STREAM_DEPTH) && f.is<rs2::video_frame>()) other_frames.push_back(f); });
262  else
263  frames.foreach_rs([this, &other_frames](const rs2::frame& f) {if (f.get_profile().stream_type() == _to_stream_type) other_frames.push_back(f); });
264 
266  {
267  for (auto from : other_frames)
268  {
269  auto aligned_frame = allocate_aligned_frame(source, from, depth);
270  align_frames(aligned_frame, from, depth);
271  output_frames.push_back(aligned_frame);
272  }
273  }
274  else
275  {
276  auto to = other_frames.front();
277  auto aligned_frame = allocate_aligned_frame(source, depth, to);
278  align_frames(aligned_frame, depth, to);
279  output_frames.push_back(aligned_frame);
280  }
281 
282  auto new_composite = source.allocate_composite_frame(std::move(output_frames));
283  return new_composite;
284  }
285 }
format
GLint GLint GLsizei GLint GLenum format
Definition: glad/glad/glad.h:1412
librealsense::align_images
void align_images(const rs2_intrinsics &depth_intrin, const rs2_extrinsics &depth_to_other, const rs2_intrinsics &other_intrin, GET_DEPTH get_depth, TRANSFER_PIXEL transfer_pixel)
Definition: align.cpp:18
librealsense
Definition: calibration-model.h:9
test-emitter-frequency.depth_profile
depth_profile
Definition: test-emitter-frequency.py:49
librealsense::align::align_z_to_other
virtual void align_z_to_other(rs2::video_frame &aligned, const rs2::video_frame &depth, const rs2::video_stream_profile &other_profile, float z_scale)
Definition: align.cpp:66
rs2::stream_profile::format
rs2_format format() const
Definition: rs_frame.hpp:44
pyglet_pointcloud_viewer.other_format
other_format
Definition: pyglet_pointcloud_viewer.py:107
librealsense::align::_to_stream_type
rs2_stream _to_stream_type
Definition: align.h:47
RS2_FORMAT_RGBA8
@ RS2_FORMAT_RGBA8
Definition: rs_sensor.h:68
min
int min(int a, int b)
Definition: lz4s.c:73
rs2::frame
Definition: rs_frame.hpp:345
rs2::video_stream_profile::clone
stream_profile clone(rs2_stream type, int index, rs2_format format, int width, int height, const rs2_intrinsics &intr) const
Definition: rs_frame.hpp:268
rs2::frame_source
Definition: rs_processing.hpp:18
rs-imu-calibration.input
input
Definition: rs-imu-calibration.py:42
align.h
rs2::frameset
Definition: rs_frame.hpp:947
rs2_transform_point_to_point
void rs2_transform_point_to_point(float to_point[3], const rs2_extrinsics *extrin, const float from_point[3])
rs2_extrinsics
Cross-stream extrinsics: encodes the topology describing how the different devices are oriented.
Definition: rs_sensor.h:98
rs2::stream_profile::fps
int fps() const
Definition: rs_frame.hpp:49
rs2::stream_profile::as
T as() const
Definition: rs_frame.hpp:103
uint16_t
unsigned short uint16_t
Definition: stdint.h:79
profile::format
rs2_format format
Definition: unit-tests-common.h:62
rs2_extension
rs2_extension
Specifies advanced interfaces (capabilities) objects may implement.
Definition: rs_types.h:166
b
GLboolean GLboolean GLboolean b
Definition: glad/glad/glad.h:3064
rs2_intrinsics
Video stream intrinsics.
Definition: rs_types.h:58
index
GLuint index
Definition: glad/glad/glad.h:2777
video.h
RS2_FORMAT_RGB8
@ RS2_FORMAT_RGB8
Definition: rs_sensor.h:66
rs2_intrinsics::height
int height
Definition: rs_types.h:61
boost::move
typename ::boost::move_detail::remove_reference< T >::type && move(T &&t) BOOST_NOEXCEPT
Definition: utility_core.hpp:191
rs2::stream_profile::stream_type
rs2_stream stream_type() const
Definition: rs_frame.hpp:39
librealsense::bytes
Definition: align.cpp:15
librealsense::align::create_aligned_profile
std::shared_ptr< rs2::video_stream_profile > create_aligned_profile(rs2::video_stream_profile &original_profile, rs2::video_stream_profile &to_profile)
Definition: align.cpp:146
librealsense::align::_align_stream_unique_ids
std::map< std::pair< stream_profile_interface *, stream_profile_interface * >, std::shared_ptr< rs2::video_stream_profile > > _align_stream_unique_ids
Definition: align.h:48
rs2::frame::get_data
const void * get_data() const
Definition: rs_frame.hpp:547
rs2_deproject_pixel_to_point
void rs2_deproject_pixel_to_point(float point[3], const rs2_intrinsics *intrin, const float pixel[2], float depth)
RS2_FORMAT_Z16
@ RS2_FORMAT_Z16
Definition: rs_sensor.h:62
librealsense::align::_depth_scale
float _depth_scale
Definition: align.h:50
librealsense::align::process_frame
rs2::frame process_frame(const rs2::frame_source &source, const rs2::frame &f) override
Definition: align.cpp:249
test-d405-calibration-stream.frames
frames
Definition: test-d405-calibration-stream.py:33
librealsense::align::reset_cache
virtual void reset_cache(rs2_stream from, rs2_stream to)
Definition: align.h:29
rs2_format
rs2_format
A stream's format identifies how binary data is encoded within a frame.
Definition: rs_sensor.h:59
librealsense::align::allocate_aligned_frame
rs2::video_frame allocate_aligned_frame(const rs2::frame_source &source, const rs2::video_frame &from, const rs2::video_frame &to)
Definition: align.cpp:209
rs2::video_stream_profile
Definition: rs_frame.hpp:201
f
GLdouble f
Definition: glad/glad/glad.h:1517
rs2_stream_profile::profile
librealsense::stream_profile_interface * profile
Definition: context.h:34
synthetic-stream.h
RS2_STREAM_DEPTH
@ RS2_STREAM_DEPTH
Definition: rs_sensor.h:45
librealsense::align_other_to_depth_bytes
void align_other_to_depth_bytes(byte *other_aligned_to_depth, GET_DEPTH get_depth, const rs2_intrinsics &depth_intrin, const rs2_extrinsics &depth_to_other, const rs2_intrinsics &other_intrin, const byte *other_pixels)
Definition: align.cpp:93
RS2_EXTENSION_VIDEO_FRAME
@ RS2_EXTENSION_VIDEO_FRAME
Definition: rs_types.h:176
rs2::video_frame::get_width
int get_width() const
Definition: rs_frame.hpp:661
librealsense::depth_frame
Definition: frame.h:295
librealsense::to_profile
stream_profile to_profile(const stream_profile_interface *sp)
Definition: src/stream.h:185
pyglet_pointcloud_viewer.other_profile
other_profile
Definition: pyglet_pointcloud_viewer.py:156
librealsense::align_other_to_depth
void align_other_to_depth(byte *other_aligned_to_depth, GET_DEPTH get_depth, const rs2_intrinsics &depth_intrin, const rs2_extrinsics &depth_to_other, const rs2_intrinsics &other_intrin, const byte *other_pixels, rs2_format other_format)
Definition: align.cpp:102
rs2::stream_profile::get
const rs2_stream_profile * get() const
Definition: rs_frame.hpp:137
source
GLsizei GLsizei GLchar * source
Definition: glad/glad/glad.h:2828
librealsense::stream
Definition: src/stream.h:14
librealsense::frame
Definition: frame.h:187
librealsense::align::align
align(rs2_stream to_stream)
Definition: align.cpp:63
rs2_project_point_to_pixel
void rs2_project_point_to_pixel(float pixel[2], const rs2_intrinsics *intrin, const float point[3])
assert
#define assert(condition)
Definition: lz4.c:245
RS2_EXTENSION_DEPTH_FRAME
@ RS2_EXTENSION_DEPTH_FRAME
Definition: rs_types.h:180
rs2_intrinsics::width
int width
Definition: rs_types.h:60
rs2::depth_frame
Definition: rs_frame.hpp:813
RS2_FORMAT_Y16
@ RS2_FORMAT_Y16
Definition: rs_sensor.h:71
librealsense::align::align_other_to_z
virtual void align_other_to_z(rs2::video_frame &aligned, const rs2::video_frame &depth, const rs2::video_frame &other, float z_scale)
Definition: align.cpp:126
rs2::frame::get_profile
stream_profile get_profile() const
Definition: rs_frame.hpp:559
librealsense::align::align_frames
void align_frames(rs2::video_frame &aligned, const rs2::video_frame &from, const rs2::video_frame &to)
Definition: align.cpp:232
librealsense::align
Definition: align.h:15
environment.h
RS2_FORMAT_Y8
@ RS2_FORMAT_Y8
Definition: rs_sensor.h:70
librealsense::align::select_extension
virtual rs2_extension select_extension(const rs2::frame &input)
Definition: align.cpp:203
rs2::video_frame
Definition: rs_frame.hpp:638
rs2::video_frame::get_bytes_per_pixel
int get_bytes_per_pixel() const
Definition: rs_frame.hpp:709
x
GLdouble x
Definition: glad/glad/glad.h:2279
librealsense::align::should_process
bool should_process(const rs2::frame &frame) override
Definition: align.cpp:178
rs2::stream_profile::stream_index
int stream_index() const
Definition: rs_frame.hpp:34
RS2_FORMAT_BGRA8
@ RS2_FORMAT_BGRA8
Definition: rs_sensor.h:69
it
static auto it
Definition: openvino-face-detection.cpp:373
rs2_stream
rs2_stream
Streams are different types of data provided by RealSense devices.
Definition: rs_sensor.h:42
RS2_FORMAT_BGR8
@ RS2_FORMAT_BGR8
Definition: rs_sensor.h:67
profile
Definition: unit-tests-common.h:59
rs2::video_frame::get_height
int get_height() const
Definition: rs_frame.hpp:673
depth
GLint GLint GLsizei GLsizei GLsizei depth
Definition: glad/glad/glad.h:2398
y
GLint y
Definition: glad/glad/glad.h:1397


librealsense2
Author(s): LibRealSense ROS Team
autogenerated on Thu Dec 22 2022 03:13:13